From 370a1318a165cba9d5c80abd18a01156314116b0 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Sat, 28 Oct 2023 17:26:03 +0200 Subject: [PATCH] Use nullptr (c++11 standard) instead of NULL --- .../visp-compute-chessboard-poses.cpp | 2 +- demo/wireframe-simulator/servoSimu4Points.cpp | 8 +- .../wireframe-simulator/servoSimuCylinder.cpp | 8 +- demo/wireframe-simulator/servoSimuSphere.cpp | 8 +- .../simulateCircle2DCamVelocity.cpp | 25 +- ...mulateFourPoints2DCartesianCamVelocity.cpp | 25 +- .../simulateFourPoints2DPolarCamVelocity.cpp | 25 +- example/device/display/displayD3D.cpp | 8 +- example/device/display/displayGDI.cpp | 8 +- example/device/display/displayGTK.cpp | 8 +- example/device/display/displayOpenCV.cpp | 8 +- example/device/display/displaySequence.cpp | 43 ++-- example/device/display/displayX.cpp | 8 +- example/device/display/displayXMulti.cpp | 8 +- example/device/framegrabber/grab1394CMU.cpp | 9 +- example/device/framegrabber/grab1394Two.cpp | 59 +++-- .../device/framegrabber/grabDirectShow.cpp | 4 +- .../framegrabber/grabDirectShowMulti.cpp | 4 +- example/device/framegrabber/grabDisk.cpp | 6 +- .../device/framegrabber/grabFlyCapture.cpp | 6 +- example/device/framegrabber/grabRealSense.cpp | 4 +- .../device/framegrabber/grabRealSense2.cpp | 4 +- example/device/framegrabber/grabV4l2.cpp | 4 +- .../framegrabber/grabV4l2MultiCpp11Thread.cpp | 14 +- .../device/framegrabber/readRealSenseData.cpp | 4 +- .../device/framegrabber/saveRealSenseData.cpp | 20 +- .../device/laserscanner/SickLDMRS-Process.cpp | 26 +- example/device/light/ringLight.cpp | 4 +- .../photometricVisualServoing.cpp | 6 +- ...hotometricVisualServoingWithoutVpServo.cpp | 6 +- example/homography/homographyHLM2DObject.cpp | 4 +- example/homography/homographyHLM3DObject.cpp | 4 +- .../homographyHartleyDLT2DObject.cpp | 4 +- .../homography/homographyRansac2DObject.cpp | 4 +- example/image/imageDiskRW.cpp | 8 +- .../manual/ogre/HelloWorldOgreAdvanced.cpp | 2 +- example/manual/simulation/manSimu4Dots.cpp | 2 +- example/manual/simulation/manSimu4Points.cpp | 2 +- example/math/BSpline.cpp | 12 +- example/math/quadprog.cpp | 2 +- example/math/quadprog_eq.cpp | 2 +- example/moments/image/servoMomentImage.cpp | 2 +- example/moments/points/servoMomentPoints.cpp | 4 +- .../moments/polygon/servoMomentPolygon.cpp | 4 +- example/ogre-simulator/AROgre.cpp | 12 +- example/ogre-simulator/AROgreBasic.cpp | 6 +- example/parse-argv/parse-argv1.cpp | 4 +- example/parse-argv/parse-argv2.cpp | 18 +- example/pose-estimation/poseVirtualVS.cpp | 6 +- .../servoSimuAfma6FourPoints2DCamVelocity.cpp | 4 +- .../camera/servoSimu3D_cMcd_CamVelocity.cpp | 4 +- ...oSimu3D_cMcd_CamVelocityWithoutVpServo.cpp | 4 +- .../camera/servoSimu3D_cdMc_CamVelocity.cpp | 4 +- ...oSimu3D_cdMc_CamVelocityWithoutVpServo.cpp | 4 +- .../camera/servoSimuCircle2DCamVelocity.cpp | 4 +- .../servoSimuCircle2DCamVelocityDisplay.cpp | 4 +- .../servoSimuCylinder2DCamVelocityDisplay.cpp | 4 +- ...inder2DCamVelocityDisplaySecondaryTask.cpp | 4 +- .../servoSimuFourPoints2DCamVelocity.cpp | 4 +- ...ervoSimuFourPoints2DCamVelocityDisplay.cpp | 4 +- ...imuFourPoints2DPolarCamVelocityDisplay.cpp | 4 +- .../servoSimuLine2DCamVelocityDisplay.cpp | 4 +- .../camera/servoSimuPoint2DCamVelocity1.cpp | 4 +- .../camera/servoSimuPoint2DCamVelocity2.cpp | 4 +- .../camera/servoSimuPoint2DCamVelocity3.cpp | 4 +- .../servoSimuPoint2DhalfCamVelocity1.cpp | 4 +- .../servoSimuPoint2DhalfCamVelocity2.cpp | 4 +- .../servoSimuPoint2DhalfCamVelocity3.cpp | 4 +- .../camera/servoSimuPoint3DCamVelocity.cpp | 4 +- .../camera/servoSimuSphere2DCamVelocity.cpp | 4 +- .../servoSimuSphere2DCamVelocityDisplay.cpp | 4 +- ...phere2DCamVelocityDisplaySecondaryTask.cpp | 4 +- ...ervoSimuSquareLine2DCamVelocityDisplay.cpp | 4 +- .../camera/servoSimuThetaUCamVelocity.cpp | 4 +- ...rvoSimuViper850FourPoints2DCamVelocity.cpp | 4 +- example/servo-afma4/moveAfma4.cpp | 4 +- .../servoAfma4Point2DCamVelocityKalman.cpp | 4 +- example/servo-biclops/moveBiclops.cpp | 4 +- .../servoBiclopsPoint2DArtVelocity.cpp | 4 +- example/servo-pioneer/sonarPioneerReader.cpp | 8 +- .../servoViper850Point2DCamVelocityKalman.cpp | 2 +- example/tools/histogram.cpp | 8 +- example/tools/parallelPort.cpp | 4 +- example/tracking/mbtEdgeKltTracking.cpp | 6 +- example/tracking/mbtEdgeTracking.cpp | 6 +- example/tracking/mbtGenericTracking.cpp | 8 +- example/tracking/mbtGenericTracking2.cpp | 8 +- example/tracking/mbtGenericTrackingDepth.cpp | 8 +- .../tracking/mbtGenericTrackingDepthOnly.cpp | 8 +- example/tracking/mbtKltTracking.cpp | 6 +- example/tracking/templateTracker.cpp | 16 +- example/tracking/trackDot.cpp | 6 +- example/tracking/trackDot2.cpp | 6 +- .../tracking/trackDot2WithAutoDetection.cpp | 6 +- example/tracking/trackKltOpencv.cpp | 6 +- example/tracking/trackMeCircle.cpp | 6 +- example/tracking/trackMeEllipse.cpp | 10 +- example/tracking/trackMeLine.cpp | 6 +- example/tracking/trackMeNurbs.cpp | 6 +- example/video/imageSequenceReader.cpp | 6 +- example/video/videoReader.cpp | 6 +- .../wireframeSimulator.cpp | 4 +- modules/ar/include/visp3/ar/vpAROgre.h | 2 +- modules/ar/include/visp3/ar/vpSimulator.h | 2 +- modules/ar/src/coin-simulator/vpAR.cpp | 4 +- modules/ar/src/coin-simulator/vpSimulator.cpp | 88 +++---- modules/ar/src/coin-simulator/vpViewer.cpp | 8 +- modules/ar/src/ogre-simulator/vpAROgre.cpp | 4 +- modules/core/include/visp3/core/vpArray2D.h | 56 ++--- modules/core/include/visp3/core/vpColVector.h | 8 +- modules/core/include/visp3/core/vpDebug.h | 6 +- modules/core/include/visp3/core/vpException.h | 2 +- modules/core/include/visp3/core/vpImage.h | 92 ++++---- .../core/include/visp3/core/vpImageConvert.h | 2 +- .../core/include/visp3/core/vpImageTools.h | 6 +- modules/core/include/visp3/core/vpList.h | 18 +- modules/core/include/visp3/core/vpMatrix.h | 12 +- modules/core/include/visp3/core/vpMoment.h | 2 +- modules/core/include/visp3/core/vpMutex.h | 10 +- modules/core/include/visp3/core/vpNetwork.h | 4 +- modules/core/include/visp3/core/vpRansac.h | 10 +- modules/core/include/visp3/core/vpRowVector.h | 8 +- modules/core/include/visp3/core/vpThread.h | 10 +- modules/core/include/visp3/core/vpXmlParser.h | 2 +- .../src/camera/vpMeterPixelConversion.cpp | 4 +- .../src/camera/vpPixelMeterConversion.cpp | 6 +- modules/core/src/display/vpDisplay.cpp | 4 +- modules/core/src/display/vpDisplay_impl.h | 88 +++---- modules/core/src/image/private/stb_truetype.h | 80 +++---- modules/core/src/image/vpGaussianFilter.cpp | 4 +- modules/core/src/image/vpImageConvert.cpp | 28 +-- modules/core/src/math/matrix/vpColVector.cpp | 26 +- modules/core/src/math/matrix/vpMatrix.cpp | 78 +++--- modules/core/src/math/matrix/vpRowVector.cpp | 16 +- .../core/src/math/matrix/vpSubColVector.cpp | 8 +- modules/core/src/math/matrix/vpSubMatrix.cpp | 6 +- .../core/src/math/matrix/vpSubRowVector.cpp | 8 +- .../cpu-features/x86/cpu_x86_Windows.ipp | 2 +- modules/core/src/tools/file/vpIoTools.cpp | 6 +- .../core/src/tools/geometry/vpPolygon3D.cpp | 12 +- .../core/src/tools/histogram/vpHistogram.cpp | 34 +-- modules/core/src/tools/network/vpClient.cpp | 2 +- modules/core/src/tools/network/vpNetwork.cpp | 6 +- modules/core/src/tools/network/vpServer.cpp | 2 +- .../core/src/tools/network/vpUDPClient.cpp | 10 +- .../core/src/tools/network/vpUDPServer.cpp | 16 +- modules/core/src/tools/serial/vpSerial.cpp | 2 +- modules/core/src/tools/xml/vpXmlParser.cpp | 42 ++-- .../core/src/tracking/moments/vpMoment.cpp | 2 +- .../image-with-dataset/testConversion.cpp | 22 +- .../core/test/image-with-dataset/testCrop.cpp | 8 +- .../image-with-dataset/testCropAdvanced.cpp | 8 +- .../testImageComparison.cpp | 6 +- .../image-with-dataset/testImageFilter.cpp | 4 +- .../testImageNormalizedCorrelation.cpp | 10 +- .../testImageTemplateMatching.cpp | 8 +- .../test/image-with-dataset/testIoPGM.cpp | 8 +- .../test/image-with-dataset/testIoPPM.cpp | 8 +- .../image-with-dataset/testPerformanceLUT.cpp | 8 +- .../test/image-with-dataset/testReadImage.cpp | 4 +- .../image-with-dataset/testUndistortImage.cpp | 8 +- .../core/test/math/testMatrixDeterminant.cpp | 4 +- modules/core/test/math/testMatrixInverse.cpp | 4 +- .../test/math/testMatrixPseudoInverse.cpp | 4 +- modules/core/test/math/testRobust.cpp | 8 +- modules/core/test/math/testSvd.cpp | 4 +- .../core/test/tools/geometry/testPolygon.cpp | 4 +- .../histogram-with-dataset/testHistogram.cpp | 6 +- .../core/test/tools/threading/testThread2.cpp | 2 +- modules/core/test/tools/xml/testXmlParser.cpp | 8 +- .../visp3/detection/vpDetectorAprilTag.h | 6 +- .../src/barcode/vpDetectorDataMatrixCode.cpp | 10 +- .../src/barcode/vpDetectorQRCode.cpp | 2 +- .../detection/src/tag/vpDetectorAprilTag.cpp | 22 +- .../gui/include/visp3/gui/vpDisplayOpenCV.h | 4 +- .../gui/include/visp3/gui/vpDisplayWin32.h | 2 +- modules/gui/include/visp3/gui/vpDisplayX.h | 4 +- modules/gui/include/visp3/gui/vpPlot.h | 2 +- modules/gui/include/visp3/gui/vpPlotGraph.h | 2 +- modules/gui/include/visp3/gui/vpWin32Window.h | 2 +- modules/gui/src/display/vpDisplayGTK.cpp | 34 +-- modules/gui/src/display/vpDisplayOpenCV.cpp | 40 ++-- modules/gui/src/display/vpDisplayX.cpp | 30 +-- .../gui/src/display/windows/vpD3DRenderer.cpp | 56 ++--- .../src/display/windows/vpDisplayWin32.cpp | 4 +- .../gui/src/display/windows/vpGDIRenderer.cpp | 30 +-- .../gui/src/display/windows/vpWin32API.cpp | 10 +- .../gui/src/display/windows/vpWin32Window.cpp | 50 ++-- modules/gui/src/plot/vpPlot.cpp | 12 +- modules/gui/src/plot/vpPlotGraph.cpp | 6 +- .../test/display-with-dataset/testClick.cpp | 8 +- .../testDisplayScaled.cpp | 4 +- .../display-with-dataset/testMouseEvent.cpp | 8 +- .../display-with-dataset/testVideoDevice.cpp | 8 +- .../test/display/testDisplayPolygonLines.cpp | 4 +- modules/gui/test/display/testDisplayRoi.cpp | 4 +- modules/gui/test/display/testDisplays.cpp | 4 +- .../gui/test/display/testVideoDeviceDual.cpp | 6 +- .../include/visp3/imgproc/vpContours.h | 24 +- modules/imgproc/src/vpContours.cpp | 12 +- .../test/with-dataset/testAutoThreshold.cpp | 8 +- .../with-dataset/testConnectedComponents.cpp | 8 +- .../test/with-dataset/testContours.cpp | 8 +- .../test/with-dataset/testFloodFill.cpp | 8 +- .../imgproc/test/with-dataset/testImgproc.cpp | 8 +- modules/io/include/visp3/io/vpImageQueue.h | 8 +- modules/io/include/visp3/io/vpParseArgv.h | 14 +- .../io/src/image/private/vpImageIoLibjpeg.cpp | 8 +- .../io/src/image/private/vpImageIoLibpng.cpp | 44 ++-- .../src/image/private/vpImageIoPortable.cpp | 12 +- modules/io/src/image/private/vpImageIoStb.cpp | 4 +- .../io/src/image/private/vpImageIoTinyEXR.cpp | 8 +- modules/io/src/tools/vpKeyboard.cpp | 2 +- modules/io/src/tools/vpParseArgv.cpp | 36 +-- modules/io/src/video/vpVideoReader.cpp | 16 +- modules/java/generator/gen2.py | 42 ++-- modules/java/generator/gen_java.py | 4 +- modules/java/generator/hdr_parser.py | 2 +- .../java/generator/src/cpp/VpImageRGBa.cpp | 12 +- .../java/generator/src/cpp/VpImageUChar.cpp | 12 +- .../java/generator/src/cpp/listconverters.cpp | 16 +- modules/java/misc/core/gen_dict.json | 6 +- .../misc/core/src/java/core+VpImageRGBa.java | 2 +- .../misc/core/src/java/core+VpImageUChar.java | 2 +- modules/java/misc/detection/gen_dict.json | 8 +- .../imgproc/src/java/imgproc+VpContour.java | 2 +- modules/java/misc/mbt/gen_dict.json | 42 ++-- .../visp3/robot/vpRobotWireFrameSimulator.h | 2 +- .../include/visp3/robot/vpSimulatorAfma6.h | 2 +- .../src/haptic-device/virtuose/vpVirtuose.cpp | 8 +- .../src/image-simulator/vpImageSimulator.cpp | 8 +- .../src/real-robot/afma4/vpRobotAfma4.cpp | 73 +++--- .../src/real-robot/afma4/vpServolens.cpp | 2 +- .../robot/src/real-robot/afma6/vpAfma6.cpp | 4 +- .../src/real-robot/afma6/vpRobotAfma6.cpp | 18 +- .../src/real-robot/bebop2/vpRobotBebop2.cpp | 172 +++++++------- .../private/vpRobotBiclopsController_impl.cpp | 2 +- .../private/vpRobotBiclopsController_impl.h | 4 +- .../src/real-robot/biclops/vpRobotBiclops.cpp | 2 +- .../real-robot/flir-ptu/vpRobotFlirPtu.cpp | 24 +- .../src/real-robot/franka/vpRobotFranka.cpp | 16 +- .../src/real-robot/kinova/vpRobotKinova.cpp | 10 +- .../src/real-robot/mavsdk/vpRobotMavsdk.cpp | 2 +- .../vpRobotUniversalRobots.cpp | 2 +- .../src/real-robot/viper/vpRobotViper650.cpp | 16 +- .../src/real-robot/viper/vpRobotViper850.cpp | 16 +- .../robot/src/real-robot/viper/vpViper650.cpp | 4 +- .../robot/src/real-robot/viper/vpViper850.cpp | 4 +- .../src/robot-simulator/vpRobotCamera.cpp | 4 +- .../vpRobotWireFrameSimulator.cpp | 4 +- .../src/robot-simulator/vpSimulatorAfma6.cpp | 24 +- .../src/robot-simulator/vpSimulatorCamera.cpp | 4 +- .../robot-simulator/vpSimulatorPioneer.cpp | 4 +- .../robot-simulator/vpSimulatorPioneerPan.cpp | 4 +- .../robot-simulator/vpSimulatorViper850.cpp | 16 +- modules/robot/src/vpRobot.cpp | 12 +- .../include/visp3/sensor/vp1394TwoGrabber.h | 10 +- .../visp3/sensor/vpOccipitalStructure.h | 32 +-- .../include/visp3/sensor/vpPylonGrabber.h | 2 +- .../sensor/include/visp3/sensor/vpRealSense.h | 10 +- .../include/visp3/sensor/vpRealSense2.h | 32 +-- .../sensor/include/visp3/sensor/vpSickLDMRS.h | 2 +- .../include/visp3/sensor/vpUeyeGrabber.h | 4 +- .../include/visp3/sensor/vpV4l2Grabber.h | 6 +- modules/sensor/src/force-torque/vpComedi.cpp | 10 +- .../force-torque/vpForceTorqueAtiSensor.cpp | 10 +- .../framegrabber/1394/vp1394CMUGrabber.cpp | 6 +- .../framegrabber/1394/vp1394TwoGrabber.cpp | 64 ++--- .../directshow/vpDirectShowGrabberImpl.cpp | 76 +++--- .../directshow/vpDirectShowSampleGrabberI.cpp | 6 +- .../flycapture/vpFlyCaptureGrabber.cpp | 4 +- .../src/framegrabber/pylon/vpPylonFactory.cpp | 4 +- .../framegrabber/pylon/vpPylonGrabberGigE.cpp | 4 +- .../framegrabber/pylon/vpPylonGrabberUsb.cpp | 4 +- .../src/framegrabber/ueye/vpUeyeGrabber.cpp | 44 ++-- .../framegrabber/ueye/vpUeyeGrabber_impl.h | 6 +- .../src/framegrabber/v4l2/vpV4l2Grabber.cpp | 80 +++---- .../src/laserscanner/sick/vpSickLDMRS.cpp | 4 +- modules/sensor/src/mocap/vpMocapQualisys.cpp | 2 +- .../vpOccipitalStructure.cpp | 156 ++++++------ .../src/rgb-depth/realsense/vpRealSense.cpp | 110 ++++----- .../src/rgb-depth/realsense/vpRealSense2.cpp | 222 +++++++++--------- .../testForceTorqueAtiNetFTSensor.cpp | 2 +- .../force-torque/testForceTorqueIitSensor.cpp | 2 +- .../testOccipitalStructure_Core_pcl.cpp | 4 +- .../test/rgb-depth/testRealSense2_D435.cpp | 4 +- .../rgb-depth/testRealSense2_D435_align.cpp | 8 +- .../rgb-depth/testRealSense2_D435_pcl.cpp | 8 +- .../test/rgb-depth/testRealSense2_SR300.cpp | 8 +- .../testRealSense2_T265_images_odometry.cpp | 2 +- .../rgb-depth/testRealSense2_T265_imu.cpp | 2 +- .../testRealSense2_T265_odometry.cpp | 4 +- .../testRealSense2_T265_undistort.cpp | 2 +- .../test/rgb-depth/testRealSense_R200.cpp | 12 +- .../test/rgb-depth/testRealSense_SR300.cpp | 26 +- .../tracker/blob/include/visp3/blob/vpDot2.h | 2 +- modules/tracker/blob/src/dots/vpDot2.cpp | 10 +- .../tracking-with-dataset/testTrackDot.cpp | 6 +- .../klt/include/visp3/klt/vpKltOpencv.h | 2 +- .../include/visp3/mbt/vpMbEdgeKltTracker.h | 2 +- .../include/visp3/mbt/vpMbGenericTracker.h | 6 +- .../mbt/include/visp3/mbt/vpMbHiddenFaces.h | 26 +- .../mbt/include/visp3/mbt/vpMbTracker.h | 8 +- .../include/visp3/mbt/vpMbtDistanceCircle.h | 12 +- .../include/visp3/mbt/vpMbtDistanceCylinder.h | 14 +- .../visp3/mbt/vpMbtDistanceKltCylinder.h | 2 +- .../visp3/mbt/vpMbtDistanceKltPoints.h | 6 +- .../mbt/include/visp3/mbt/vpMbtDistanceLine.h | 10 +- .../include/visp3/mbt/vpMbtFaceDepthDense.h | 8 +- .../include/visp3/mbt/vpMbtFaceDepthNormal.h | 8 +- .../mbt/include/visp3/mbt/vpMbtMeEllipse.h | 2 +- .../mbt/src/depth/vpMbDepthDenseTracker.cpp | 6 +- .../mbt/src/depth/vpMbDepthNormalTracker.cpp | 6 +- .../mbt/src/depth/vpMbtFaceDepthDense.cpp | 4 +- .../mbt/src/depth/vpMbtFaceDepthNormal.cpp | 4 +- .../tracker/mbt/src/edge/vpMbEdgeTracker.cpp | 114 ++++----- .../mbt/src/edge/vpMbtDistanceCircle.cpp | 30 +-- .../mbt/src/edge/vpMbtDistanceCylinder.cpp | 48 ++-- .../mbt/src/edge/vpMbtDistanceLine.cpp | 38 +-- .../tracker/mbt/src/edge/vpMbtMeEllipse.cpp | 4 +- modules/tracker/mbt/src/edge/vpMbtMeLine.cpp | 2 +- .../mbt/src/hybrid/vpMbEdgeKltTracker.cpp | 38 +-- .../tracker/mbt/src/klt/vpMbKltTracker.cpp | 40 ++-- .../mbt/src/klt/vpMbtDistanceKltCylinder.cpp | 2 +- .../mbt/src/klt/vpMbtDistanceKltPoints.cpp | 8 +- .../tracker/mbt/src/vpMbGenericTracker.cpp | 84 +++---- modules/tracker/mbt/src/vpMbScanLine.cpp | 6 +- modules/tracker/mbt/src/vpMbTracker.cpp | 116 ++++----- .../tracker/mbt/src/vpMbtXmlGenericParser.cpp | 2 +- .../testGenericTracker.cpp | 6 +- .../testGenericTrackerDepth.cpp | 6 +- .../tracker/mbt/test/testTukeyEstimator.cpp | 2 +- .../tracker/me/include/visp3/me/vpMeEllipse.h | 8 +- .../tracker/me/include/visp3/me/vpMeTracker.h | 2 +- modules/tracker/me/src/moving-edges/vpMe.cpp | 18 +- .../me/src/moving-edges/vpMeEllipse.cpp | 2 +- .../tracker/me/src/moving-edges/vpMeNurbs.cpp | 38 +-- .../me/src/moving-edges/vpMeTracker.cpp | 6 +- .../tracker/me/src/moving-edges/vpNurbs.cpp | 16 +- modules/tracker/me/test/testNurbs.cpp | 12 +- .../tt/include/visp3/tt/vpTemplateTracker.h | 16 +- .../visp3/tt/vpTemplateTrackerHeader.h | 6 +- modules/tracker/tt/src/vpTemplateTracker.cpp | 48 ++-- .../include/visp3/tt_mi/vpTemplateTrackerMI.h | 8 +- .../tt_mi/src/mi/vpTemplateTrackerMI.cpp | 4 +- .../include/visp3/vision/vpHomography.h | 2 +- .../vision/include/visp3/vision/vpKeyPoint.h | 60 ++--- modules/vision/include/visp3/vision/vpPose.h | 26 +- .../include/visp3/vision/vpPoseFeatures.h | 4 +- .../homography-estimation/vpHomography.cpp | 2 +- .../vpHomographyRansac.cpp | 2 +- modules/vision/src/key-point/vpKeyPoint.cpp | 54 ++--- modules/vision/src/pose-estimation/vpPose.cpp | 10 +- .../src/pose-estimation/vpPoseLagrange.cpp | 6 +- .../vision/src/pose-estimation/vpPoseRGBD.cpp | 8 +- .../src/pose-estimation/vpPoseRansac.cpp | 6 +- .../keypoint-with-dataset/testKeyPoint-2.cpp | 4 +- .../keypoint-with-dataset/testKeyPoint-3.cpp | 4 +- .../keypoint-with-dataset/testKeyPoint-4.cpp | 4 +- .../keypoint-with-dataset/testKeyPoint-5.cpp | 4 +- .../keypoint-with-dataset/testKeyPoint-6.cpp | 4 +- .../keypoint-with-dataset/testKeyPoint-7.cpp | 4 +- .../keypoint-with-dataset/testKeyPoint.cpp | 4 +- .../visp3/visual_features/vpFeatureMoment.h | 14 +- .../visual_features/vpFeatureMomentAlpha.h | 2 +- .../visual_features/vpFeatureMomentArea.h | 2 +- .../vpFeatureMomentAreaNormalized.h | 4 +- .../visual_features/vpFeatureMomentBasic.h | 2 +- .../vpFeatureMomentCInvariant.h | 4 +- .../visual_features/vpFeatureMomentCentered.h | 2 +- .../visual_features/vpFeatureMomentDatabase.h | 2 +- .../vpFeatureMomentGravityCenter.h | 4 +- .../vpFeatureMomentGravityCenterNormalized.h | 4 +- .../src/visual-feature/vpBasicFeature.cpp | 12 +- .../src/visual-feature/vpFeatureDepth.cpp | 2 +- .../src/visual-feature/vpFeatureEllipse.cpp | 2 +- .../src/visual-feature/vpFeatureLine.cpp | 2 +- .../src/visual-feature/vpFeatureLuminance.cpp | 12 +- .../src/visual-feature/vpFeatureMoment.cpp | 10 +- .../src/visual-feature/vpFeaturePoint.cpp | 2 +- .../src/visual-feature/vpFeaturePoint3D.cpp | 2 +- .../visual-feature/vpFeaturePointPolar.cpp | 2 +- .../src/visual-feature/vpFeatureSegment.cpp | 2 +- .../src/visual-feature/vpFeatureThetaU.cpp | 2 +- .../visual-feature/vpFeatureTranslation.cpp | 4 +- .../vpFeatureVanishingPoint.cpp | 2 +- modules/vs/src/vpServo.cpp | 4 +- .../visual-feature/testFeatureSegment.cpp | 14 +- ...torial-pose-from-points-realsense-T265.cpp | 8 +- .../tutorial-barcode-detector-live.cpp | 2 +- .../barcode/tutorial-barcode-detector.cpp | 2 +- .../dnn/tutorial-dnn-tensorrt-live.cpp | 8 +- .../tutorial-face-detector-live-threaded.cpp | 4 +- ...-apriltag-detector-live-T265-realsense.cpp | 8 +- ...-apriltag-detector-live-rgbd-realsense.cpp | 10 +- ...ltag-detector-live-rgbd-structure-core.cpp | 6 +- .../tag/tutorial-apriltag-detector-live.cpp | 2 +- tutorial/grabber/tutorial-grabber-1394.cpp | 2 +- .../grabber/tutorial-grabber-basler-pylon.cpp | 2 +- tutorial/grabber/tutorial-grabber-bebop2.cpp | 2 +- .../grabber/tutorial-grabber-flycapture.cpp | 2 +- .../grabber/tutorial-grabber-ids-ueye.cpp | 2 +- .../tutorial-grabber-multiple-realsense.cpp | 2 +- .../tutorial-grabber-opencv-threaded.cpp | 4 +- tutorial/grabber/tutorial-grabber-opencv.cpp | 2 +- .../tutorial-grabber-realsense-T265.cpp | 4 +- .../grabber/tutorial-grabber-realsense.cpp | 2 +- ...torial-grabber-rgbd-D435-structurecore.cpp | 2 +- .../tutorial-grabber-structure-core.cpp | 4 +- .../tutorial-grabber-v4l2-threaded.cpp | 2 +- tutorial/grabber/tutorial-grabber-v4l2.cpp | 2 +- .../project.pbxproj | 8 +- .../VispHelper/ImageConversion.mm | 5 +- .../VispHelper/ImageDisplayWithContext.h | 4 +- .../GettingStarted.xcodeproj/project.pbxproj | 4 +- .../StartedAprilTag.xcodeproj/project.pbxproj | 4 +- .../StartedAprilTag/ImageConversion.mm | 5 +- .../project.pbxproj | 4 +- .../StartedImageProc/ImageConversion.mm | 5 +- tutorial/matlab/tutorial-matlab.cpp | 2 +- .../mbot-serial-controller.ino | 16 +- .../visp/mbot-apriltag-2D-half-vs.cpp | 4 +- .../raspberry/visp/mbot-apriltag-ibvs.cpp | 4 +- .../raspberry/visp/mbot-apriltag-pbvs.cpp | 4 +- ...torial-mb-generic-tracker-apriltag-rs2.cpp | 10 +- ...ial-mb-generic-tracker-apriltag-webcam.cpp | 2 +- ...c-tracker-rgbd-realsense-json-settings.cpp | 4 +- ...rial-mb-generic-tracker-rgbd-realsense.cpp | 4 +- ...mb-generic-tracker-rgbd-structure-core.cpp | 2 +- .../tutorial-mb-generic-tracker-full.cpp | 6 +- .../tutorial-mb-generic-tracker-live.cpp | 2 +- .../generic/tutorial-mb-generic-tracker.cpp | 2 +- .../old/generic/tutorial-mb-tracker-full.cpp | 2 +- .../old/generic/tutorial-mb-tracker.cpp | 2 +- 434 files changed, 2682 insertions(+), 2656 deletions(-) diff --git a/apps/calibration/visp-compute-chessboard-poses.cpp b/apps/calibration/visp-compute-chessboard-poses.cpp index ffb68ffd81..9c095bf1b3 100644 --- a/apps/calibration/visp-compute-chessboard-poses.cpp +++ b/apps/calibration/visp-compute-chessboard-poses.cpp @@ -211,7 +211,7 @@ int main(int argc, const char **argv) #if defined(VISP_HAVE_MODULE_GUI) - vpDisplay *display = NULL; + vpDisplay *display = nullptr; if (opt_interactive) { #if defined(VISP_HAVE_X11) display = new vpDisplayX(I); diff --git a/demo/wireframe-simulator/servoSimu4Points.cpp b/demo/wireframe-simulator/servoSimu4Points.cpp index bffda5e743..39963223eb 100644 --- a/demo/wireframe-simulator/servoSimu4Points.cpp +++ b/demo/wireframe-simulator/servoSimu4Points.cpp @@ -135,7 +135,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &plot) plot = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -146,7 +146,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &plot) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -200,7 +200,7 @@ int main(int argc, const char **argv) vpDisplay::flush(Iext2); } - vpPlot *plotter = NULL; + vpPlot *plotter = nullptr; if (opt_plot) { plotter = new vpPlot(2, 480, 640, 750, 550, "Real time curves plotter"); @@ -464,7 +464,7 @@ int main(int argc, const char **argv) std::cout << "|| s - s* || = " << (task.getError()).sumSquare() << std::endl; } - if (opt_plot && plotter != NULL) { + if (opt_plot && plotter != nullptr) { vpDisplay::display(Iint); sim.getInternalImage(Iint); vpDisplay::displayFrame(Iint, cMo, camera, 0.2, vpColor::none); diff --git a/demo/wireframe-simulator/servoSimuCylinder.cpp b/demo/wireframe-simulator/servoSimuCylinder.cpp index 3a8d589dd0..870777a0ed 100644 --- a/demo/wireframe-simulator/servoSimuCylinder.cpp +++ b/demo/wireframe-simulator/servoSimuCylinder.cpp @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &plot) plot = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &plot) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -194,7 +194,7 @@ int main(int argc, const char **argv) vpDisplay::flush(Iext); } - vpPlot *plotter = NULL; + vpPlot *plotter = nullptr; vpServo task; vpSimulatorCamera robot; @@ -436,7 +436,7 @@ int main(int argc, const char **argv) std::cout << "|| s - s* || = " << (task.getError()).sumSquare() << std::endl; } - if (opt_plot && plotter != NULL) { + if (opt_plot && plotter != nullptr) { vpDisplay::display(Iint); sim.getInternalImage(Iint); vpDisplay::displayFrame(Iint, cMo, camera, 0.2, vpColor::none); diff --git a/demo/wireframe-simulator/servoSimuSphere.cpp b/demo/wireframe-simulator/servoSimuSphere.cpp index 4bbee3396c..7969244b01 100644 --- a/demo/wireframe-simulator/servoSimuSphere.cpp +++ b/demo/wireframe-simulator/servoSimuSphere.cpp @@ -131,7 +131,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &plot) plot = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -142,7 +142,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &plot) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -254,7 +254,7 @@ int main(int argc, const char **argv) vpDisplay::flush(Iext2); } - vpPlot *plotter = NULL; + vpPlot *plotter = nullptr; vpServo task; vpSimulatorCamera robot; @@ -473,7 +473,7 @@ int main(int argc, const char **argv) std::cout << "|| s - s* || = " << (task.getError()).sumSquare() << std::endl; } - if (opt_plot && plotter != NULL) { + if (opt_plot && plotter != nullptr) { vpDisplay::display(Iint); sim.getInternalImage(Iint); vpDisplay::displayFrame(Iint, cMo, camera, 0.2, vpColor::none); diff --git a/example/coin-simulator/simulateCircle2DCamVelocity.cpp b/example/coin-simulator/simulateCircle2DCamVelocity.cpp index 52b8fa09eb..060f9be702 100644 --- a/example/coin-simulator/simulateCircle2DCamVelocity.cpp +++ b/example/coin-simulator/simulateCircle2DCamVelocity.cpp @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &display) display = false; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -149,7 +149,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -282,7 +282,7 @@ static void *mainLoop(void *_simu) simu->closeMainApplication(); - void *a = NULL; + void *a = nullptr; return a; } @@ -318,19 +318,19 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_INPUT_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_INPUT_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -358,7 +358,8 @@ int main(int argc, const char **argv) simu.mainLoop(); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -370,8 +371,8 @@ int main() std::cout << "You do not have Coin3D and SoQT or SoWin or SoXt functionalities enabled..." << std::endl; std::cout << "Tip:" << std::endl; std::cout - << "- Install Coin3D and SoQT or SoWin or SoXt, configure ViSP again using cmake and build again this example" - << std::endl; + << "- Install Coin3D and SoQT or SoWin or SoXt, configure ViSP again using cmake and build again this example" + << std::endl; return EXIT_SUCCESS; } #endif diff --git a/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp b/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp index e0d0d6a947..7c5e547753 100644 --- a/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp +++ b/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &display) display = false; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -149,7 +149,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -293,7 +293,7 @@ static void *mainLoop(void *_simu) simu->closeMainApplication(); - void *a = NULL; + void *a = nullptr; return a; } @@ -329,19 +329,19 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -368,7 +368,8 @@ int main(int argc, const char **argv) simu.mainLoop(); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -380,8 +381,8 @@ int main() std::cout << "You do not have Coin3D and SoQT or SoWin or SoXt functionalities enabled..." << std::endl; std::cout << "Tip:" << std::endl; std::cout - << "- Install Coin3D and SoQT or SoWin or SoXt, configure ViSP again using cmake and build again this example" - << std::endl; + << "- Install Coin3D and SoQT or SoWin or SoXt, configure ViSP again using cmake and build again this example" + << std::endl; return EXIT_SUCCESS; } #endif diff --git a/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp b/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp index 0a8fcc62dc..aeea07dd54 100644 --- a/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp +++ b/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp @@ -134,7 +134,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &display) display = false; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -315,7 +315,7 @@ static void *mainLoop(void *_simu) simu->closeMainApplication(); - void *a = NULL; + void *a = nullptr; return a; } @@ -351,19 +351,19 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -390,7 +390,8 @@ int main(int argc, const char **argv) simu.mainLoop(); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -402,8 +403,8 @@ int main() std::cout << "You do not have Coin3D and SoQT or SoWin or SoXt functionalities enabled..." << std::endl; std::cout << "Tip:" << std::endl; std::cout - << "- Install Coin3D and SoQT or SoWin or SoXt, configure ViSP again using cmake and build again this example" - << std::endl; + << "- Install Coin3D and SoQT or SoWin or SoXt, configure ViSP again using cmake and build again this example" + << std::endl; return EXIT_SUCCESS; } #endif diff --git a/example/device/display/displayD3D.cpp b/example/device/display/displayD3D.cpp index 934b2cf5ae..0967e93bd0 100644 --- a/example/device/display/displayD3D.cpp +++ b/example/device/display/displayD3D.cpp @@ -162,7 +162,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -175,7 +175,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -232,7 +232,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(odirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << odirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -253,7 +253,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/display/displayGDI.cpp b/example/device/display/displayGDI.cpp index 17bebbd21f..c3daf5eca2 100644 --- a/example/device/display/displayGDI.cpp +++ b/example/device/display/displayGDI.cpp @@ -162,7 +162,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -175,7 +175,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -232,7 +232,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(odirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << odirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -253,7 +253,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/display/displayGTK.cpp b/example/device/display/displayGTK.cpp index a80883c498..f14e4094bf 100644 --- a/example/device/display/displayGTK.cpp +++ b/example/device/display/displayGTK.cpp @@ -165,7 +165,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -178,7 +178,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -239,7 +239,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(odirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << odirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -260,7 +260,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/display/displayOpenCV.cpp b/example/device/display/displayOpenCV.cpp index a0968ada52..f3dfed335f 100644 --- a/example/device/display/displayOpenCV.cpp +++ b/example/device/display/displayOpenCV.cpp @@ -166,7 +166,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -179,7 +179,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -240,7 +240,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(odirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << odirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -261,7 +261,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/display/displaySequence.cpp b/example/device/display/displaySequence.cpp index a6d7dd67a4..4f8cd6d4ad 100644 --- a/example/device/display/displaySequence.cpp +++ b/example/device/display/displaySequence.cpp @@ -199,7 +199,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp wait = true; break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); return false; break; @@ -212,7 +212,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -269,21 +269,21 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << " Use -p option if you want to " << std::endl - << " use personal images." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -306,19 +306,21 @@ int main(int argc, const char **argv) s.setf(std::ios::right, std::ios::adjustfield); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } // Read image named "filename" and put the bitmap in I try { vpImageIo::read(I, filename); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; std::cerr << " Check your -i " << ipath << " option, " << std::endl - << " or your -p " << opt_ppath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable" << std::endl; + << " or your -p " << opt_ppath << " option " << std::endl + << " or VISP_INPUT_IMAGE_PATH environment variable" << std::endl; return EXIT_FAILURE; } @@ -353,7 +355,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -371,8 +374,9 @@ int main(int argc, const char **argv) std::cout << "A click in the image to continue..." << std::endl; // Wait for a blocking mouse click vpDisplay::getClick(I); - } else { - // Synchronise the loop to 40 ms + } + else { + // Synchronise the loop to 40 ms vpTime::wait(tms, 40); } @@ -382,7 +386,8 @@ int main(int argc, const char **argv) // double tms_total = tms_2 - tms_1 ; // std::cout << "Total Time : "<< tms_total< option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/display/displayXMulti.cpp b/example/device/display/displayXMulti.cpp index 0981c574f6..d1ada273a4 100644 --- a/example/device/display/displayXMulti.cpp +++ b/example/device/display/displayXMulti.cpp @@ -166,7 +166,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -179,7 +179,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -240,7 +240,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(odirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << odirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -261,7 +261,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/framegrabber/grab1394CMU.cpp b/example/device/framegrabber/grab1394CMU.cpp index c10578dddc..dd48c36ea9 100644 --- a/example/device/framegrabber/grab1394CMU.cpp +++ b/example/device/framegrabber/grab1394CMU.cpp @@ -96,7 +96,7 @@ OPTIONS: Default\n\ -h \n\ Print the help.\n\ \n", - nframes, opath.c_str()); +nframes, opath.c_str()); if (badparam) { fprintf(stderr, "ERROR: \n"); fprintf(stderr, "\nBad parameter [%s]\n", badparam); @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, bool &display, unsigned int &nframe opath = optarg_; break; case 'h': - usage(argv[0], NULL, nframes, opath); + usage(argv[0], nullptr, nframes, opath); return false; break; @@ -149,7 +149,7 @@ bool getOptions(int argc, const char **argv, bool &display, unsigned int &nframe if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, nframes, opath); + usage(argv[0], nullptr, nframes, opath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -257,7 +257,8 @@ int main(int argc, const char **argv) std::cout << "Mean loop time: " << ttotal / nframes << " ms" << std::endl; std::cout << "Mean frequency: " << 1000. / (ttotal / nframes) << " fps" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/example/device/framegrabber/grab1394Two.cpp b/example/device/framegrabber/grab1394Two.cpp index 2de1d43a25..79d12ba46c 100644 --- a/example/device/framegrabber/grab1394Two.cpp +++ b/example/device/framegrabber/grab1394Two.cpp @@ -318,7 +318,7 @@ bool read_options(int argc, const char **argv, bool &multi, unsigned int &camera break; case 'h': case '?': - usage(argv[0], NULL, camera, nframes, opath, roi_left, roi_top, roi_width, roi_height, ringbuffersize, + usage(argv[0], nullptr, camera, nframes, opath, roi_left, roi_top, roi_width, roi_height, ringbuffersize, panControl); exit(0); break; @@ -327,7 +327,7 @@ bool read_options(int argc, const char **argv, bool &multi, unsigned int &camera if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, camera, nframes, opath, roi_left, roi_top, roi_width, roi_height, ringbuffersize, panControl); + usage(argv[0], nullptr, camera, nframes, opath, roi_left, roi_top, roi_width, roi_height, ringbuffersize, panControl); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -418,7 +418,8 @@ int main(int argc, const char **argv) if (multi) { camera = 0; // to over write a bad option usage - } else { + } + else { ncameras = 1; // acquisition from only one camera } // Offset is used to set the correspondancy between and image and the @@ -454,22 +455,22 @@ int main(int argc, const char **argv) g.getGuid(guid); std::cout << "----------------------------------------------------------" << std::endl - << "---- Video modes and framerates supported by camera " << i + offset << " ----" << std::endl - << "---- with guid 0x" << std::hex << guid << " ----" << std::endl - << "---- * is for the current settings ----" << std::endl - << "---- between ( ) you have the corresponding option ----" << std::endl - << "---- to use. ----" << std::endl - << "----------------------------------------------------------" << std::endl; + << "---- Video modes and framerates supported by camera " << i + offset << " ----" << std::endl + << "---- with guid 0x" << std::hex << guid << " ----" << std::endl + << "---- * is for the current settings ----" << std::endl + << "---- between ( ) you have the corresponding option ----" << std::endl + << "---- to use. ----" << std::endl + << "----------------------------------------------------------" << std::endl; for (it_lmode = lmode.begin(); it_lmode != lmode.end(); ++it_lmode) { // Parse the list of supported modes vp1394TwoGrabber::vp1394TwoVideoModeType supmode = *it_lmode; if (curmode == supmode) std::cout << " * " << vp1394TwoGrabber::videoMode2string(supmode) << " (-v " << (int)supmode << ")" - << std::endl; + << std::endl; else std::cout << " " << vp1394TwoGrabber::videoMode2string(supmode) << " (-v " << (int)supmode << ")" - << std::endl; + << std::endl; if (g.isVideoModeFormat7(supmode)) { // Format 7 video mode; no framerate setting, but color @@ -480,23 +481,24 @@ int main(int argc, const char **argv) supcoding = *it_lcoding; if ((curmode == supmode) && (supcoding == curcoding)) std::cout << " * " << vp1394TwoGrabber::colorCoding2string(supcoding) << " (-g " << (int)supcoding - << ")" << std::endl; + << ")" << std::endl; else std::cout << " " << vp1394TwoGrabber::colorCoding2string(supcoding) << " (-g " << (int)supcoding - << ")" << std::endl; + << ")" << std::endl; } - } else { + } + else { - // Parse the list of supported framerates for a supported mode + // Parse the list of supported framerates for a supported mode g.getFramerateSupported(supmode, lfps); for (it_lfps = lfps.begin(); it_lfps != lfps.end(); ++it_lfps) { vp1394TwoGrabber::vp1394TwoFramerateType supfps = *it_lfps; if ((curmode == supmode) && (supfps == curfps)) std::cout << " * " << vp1394TwoGrabber::framerate2string(supfps) << " (-f " << (int)supfps << ")" - << std::endl; + << std::endl; else std::cout << " " << vp1394TwoGrabber::framerate2string(supfps) << " (-f " << (int)supfps << ")" - << std::endl; + << std::endl; } } } @@ -516,8 +518,9 @@ int main(int argc, const char **argv) if (videomode_is_set) { g.setCamera(camera); g.setVideoMode(videomode); - } else { - // get The actual video mode + } + else { + // get The actual video mode g.setCamera(camera); g.getVideoMode(videomode); } @@ -542,7 +545,7 @@ int main(int argc, const char **argv) #ifdef VISP_HAVE_X11 // allocate a display for each camera to consider - vpDisplayX *d = NULL; + vpDisplayX *d = nullptr; if (display) d = new vpDisplayX[ncameras]; #endif @@ -562,7 +565,7 @@ int main(int argc, const char **argv) if (grab_color[i]) { g.acquire(Ic[i]); std::cout << "Image size for camera " << i + offset << " : width: " << Ic[i].getWidth() - << " height: " << Ic[i].getHeight() << std::endl; + << " height: " << Ic[i].getHeight() << std::endl; #ifdef VISP_HAVE_X11 if (display) { @@ -575,10 +578,11 @@ int main(int argc, const char **argv) vpDisplay::flush(Ic[i]); } #endif - } else { + } + else { g.acquire(Ig[i]); std::cout << "Image size for camera " << i + offset << " : width: " << Ig[i].getWidth() - << " height: " << Ig[i].getHeight() << std::endl; + << " height: " << Ig[i].getHeight() << std::endl; #ifdef VISP_HAVE_X11 if (display) { @@ -615,7 +619,8 @@ int main(int argc, const char **argv) vpDisplay::flush(Ic[c]); } #endif - } else { + } + else { g.acquire(Ig[c]); #ifdef VISP_HAVE_X11 if (display) { @@ -632,7 +637,8 @@ int main(int argc, const char **argv) std::cout << "Write: " << filename << std::endl; if (grab_color[c]) { vpImageIo::write(Ic[c], filename); - } else { + } + else { vpImageIo::write(Ig[c], filename); } } @@ -661,7 +667,8 @@ int main(int argc, const char **argv) delete[] d; #endif return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/example/device/framegrabber/grabDirectShow.cpp b/example/device/framegrabber/grabDirectShow.cpp index 8c56220d09..3e53fc53c7 100644 --- a/example/device/framegrabber/grabDirectShow.cpp +++ b/example/device/framegrabber/grabDirectShow.cpp @@ -134,7 +134,7 @@ bool getOptions(int argc, const char **argv, bool &display, unsigned &nframes, b opath = optarg; break; case 'h': - usage(argv[0], NULL, nframes, opath); + usage(argv[0], nullptr, nframes, opath); return false; break; @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, bool &display, unsigned &nframes, b if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, nframes, opath); + usage(argv[0], nullptr, nframes, opath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; diff --git a/example/device/framegrabber/grabDirectShowMulti.cpp b/example/device/framegrabber/grabDirectShowMulti.cpp index 6fb595223f..26c707b847 100644 --- a/example/device/framegrabber/grabDirectShowMulti.cpp +++ b/example/device/framegrabber/grabDirectShowMulti.cpp @@ -209,14 +209,14 @@ void read_options(int argc, const char **argv, bool &multi, unsigned int &camera mediatypeID = atoi(optarg); break; default: - usage(argv[0], NULL, camera, nframes, opath); + usage(argv[0], nullptr, camera, nframes, opath); break; } } if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, camera, nframes, opath); + usage(argv[0], nullptr, camera, nframes, opath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; } diff --git a/example/device/framegrabber/grabDisk.cpp b/example/device/framegrabber/grabDisk.cpp index 526da60602..cb4ff2dc05 100644 --- a/example/device/framegrabber/grabDisk.cpp +++ b/example/device/framegrabber/grabDisk.cpp @@ -183,7 +183,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &ba nzero = (unsigned)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, basename, ext, first, last, step, nzero); + usage(argv[0], nullptr, ipath, basename, ext, first, last, step, nzero); return false; break; @@ -196,7 +196,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &ba if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, basename, ext, first, last, step, nzero); + usage(argv[0], nullptr, ipath, basename, ext, first, last, step, nzero); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -265,7 +265,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_basename, opt_ext, opt_first, opt_last, opt_step, opt_nzero); + usage(argv[0], nullptr, ipath, opt_basename, opt_ext, opt_first, opt_last, opt_step, opt_nzero); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/device/framegrabber/grabFlyCapture.cpp b/example/device/framegrabber/grabFlyCapture.cpp index c68add1e12..ff218e7735 100644 --- a/example/device/framegrabber/grabFlyCapture.cpp +++ b/example/device/framegrabber/grabFlyCapture.cpp @@ -141,7 +141,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &click, bool &s opath = optarg_; break; case 'h': - usage(argv[0], NULL, icamera, opath); + usage(argv[0], nullptr, icamera, opath); return false; break; @@ -154,7 +154,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &click, bool &s if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, icamera, opath); + usage(argv[0], nullptr, icamera, opath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -189,7 +189,7 @@ int main(int argc, const char **argv) std::cout << "Camera serial: " << g.getCameraSerial(g.getCameraIndex()) << std::endl; std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *display = NULL; + vpDisplay *display = nullptr; if (opt_display) { #if defined(VISP_HAVE_X11) display = new vpDisplayX(I); diff --git a/example/device/framegrabber/grabRealSense.cpp b/example/device/framegrabber/grabRealSense.cpp index 517d2b3379..1c5a6bcc99 100644 --- a/example/device/framegrabber/grabRealSense.cpp +++ b/example/device/framegrabber/grabRealSense.cpp @@ -180,10 +180,10 @@ int main() } else { #ifdef VISP_HAVE_PCL - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, (unsigned char *)infrared_display.bitmap); #else - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, (unsigned char *)infrared_display.bitmap); #endif } diff --git a/example/device/framegrabber/grabRealSense2.cpp b/example/device/framegrabber/grabRealSense2.cpp index 18f5bcd345..259285372d 100644 --- a/example/device/framegrabber/grabRealSense2.cpp +++ b/example/device/framegrabber/grabRealSense2.cpp @@ -201,12 +201,12 @@ int main() #ifdef VISP_HAVE_PCL { std::lock_guard lock(mutex); - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, (unsigned char *)infrared.bitmap); update_pointcloud = true; } #else - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)infrared.bitmap); + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, (unsigned char *)infrared.bitmap); #endif vpImageConvert::createDepthHistogram(depth, depth_display); diff --git a/example/device/framegrabber/grabV4l2.cpp b/example/device/framegrabber/grabV4l2.cpp index bba25314ce..9590a57a42 100644 --- a/example/device/framegrabber/grabV4l2.cpp +++ b/example/device/framegrabber/grabV4l2.cpp @@ -212,7 +212,7 @@ bool getOptions(int argc, const char **argv, unsigned &fps, unsigned &input, uns verbose = true; break; case 'h': - usage(argv[0], NULL, fps, input, scale, niter, device, pixelformat, image_type, opath); + usage(argv[0], nullptr, fps, input, scale, niter, device, pixelformat, image_type, opath); return false; break; @@ -225,7 +225,7 @@ bool getOptions(int argc, const char **argv, unsigned &fps, unsigned &input, uns if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, fps, input, scale, niter, device, pixelformat, image_type, opath); + usage(argv[0], nullptr, fps, input, scale, niter, device, pixelformat, image_type, opath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp index ea1a2dc508..0753400e97 100644 --- a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp +++ b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp @@ -108,7 +108,7 @@ bool getOptions(int argc, char **argv, unsigned int &deviceCount, bool &saveVide saveVideo = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -121,7 +121,7 @@ bool getOptions(int argc, char **argv, unsigned int &deviceCount, bool &saveVide if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; @@ -251,11 +251,11 @@ class vpShareImage struct vpCancelled_t { }; - vpShareImage() : m_cancelled(false), m_cond(), m_mutex(), m_pImgData(NULL), m_totalSize(0) { } + vpShareImage() : m_cancelled(false), m_cond(), m_mutex(), m_pImgData(nullptr), m_totalSize(0) { } virtual ~vpShareImage() { - if (m_pImgData != NULL) { + if (m_pImgData != nullptr) { delete[] m_pImgData; } } @@ -302,10 +302,10 @@ class vpShareImage { std::lock_guard lock(m_mutex); - if (m_pImgData == NULL || m_totalSize != totalSize) { + if (m_pImgData == nullptr || m_totalSize != totalSize) { m_totalSize = totalSize; - if (m_pImgData != NULL) { + if (m_pImgData != nullptr) { delete[] m_pImgData; } @@ -387,7 +387,7 @@ void display(unsigned int width, unsigned int height, int win_x, int win_y, unsi vpImageConvert::convert(I_green_gaussian_double, I_green_gaussian); vpImageConvert::convert(I_blue_gaussian_double, I_blue_gaussian); - vpImageConvert::merge(&I_red_gaussian, &I_green_gaussian, &I_blue_gaussian, NULL, local_img); + vpImageConvert::merge(&I_red_gaussian, &I_green_gaussian, &I_blue_gaussian, nullptr, local_img); } t = vpTime::measureTimeMs() - t; diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index 43b160a9da..ac2860bdf3 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -124,7 +124,7 @@ bool getOptions(int argc, char **argv, std::string &input_directory, bool &click break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -137,7 +137,7 @@ bool getOptions(int argc, char **argv, std::string &input_directory, bool &click if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index 7548872130..989510085b 100644 --- a/example/device/framegrabber/saveRealSenseData.cpp +++ b/example/device/framegrabber/saveRealSenseData.cpp @@ -159,7 +159,7 @@ bool getOptions(int argc, char **argv, bool &save, std::string &output_directory break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -172,7 +172,7 @@ bool getOptions(int argc, char **argv, bool &save, std::string &output_directory if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; @@ -535,7 +535,7 @@ int main(int argc, char *argv[]) d3.init(I_infrared, I_gray.getWidth() + 80, I_gray.getHeight() + 10, "RealSense infrared stream"); while (true) { - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, nullptr); vpImageConvert::convert(I_color, I_gray); vpImageConvert::createDepthHistogram(I_depth_raw, I_depth); @@ -632,28 +632,28 @@ int main(int argc, char *argv[]) if (use_aligned_stream) { #ifdef USE_REALSENSE2 #ifdef VISP_HAVE_PCL - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, pointCloud, NULL, + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, pointCloud, nullptr, &align_to); #else - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointCloud, NULL, + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointCloud, nullptr, &align_to); #endif #else #ifdef VISP_HAVE_PCL - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, pointCloud, - (unsigned char *)I_infrared.bitmap, NULL, rs::stream::rectified_color, + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, pointCloud, + (unsigned char *)I_infrared.bitmap, nullptr, rs::stream::rectified_color, rs::stream::depth_aligned_to_rectified_color); #else realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointCloud, - (unsigned char *)I_infrared.bitmap, NULL, rs::stream::rectified_color, + (unsigned char *)I_infrared.bitmap, nullptr, rs::stream::rectified_color, rs::stream::depth_aligned_to_rectified_color); #endif #endif } else { #ifdef VISP_HAVE_PCL - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, pointCloud, - (unsigned char *)I_infrared.bitmap, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, pointCloud, + (unsigned char *)I_infrared.bitmap, nullptr); #else realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointCloud, (unsigned char *)I_infrared.bitmap); diff --git a/example/device/laserscanner/SickLDMRS-Process.cpp b/example/device/laserscanner/SickLDMRS-Process.cpp index 188424f736..dc1dac47b3 100644 --- a/example/device/laserscanner/SickLDMRS-Process.cpp +++ b/example/device/laserscanner/SickLDMRS-Process.cpp @@ -116,7 +116,7 @@ void *laser_display_and_save_loop(void *) } } - vpDisplay *display = NULL; + vpDisplay *display = nullptr; #ifdef VISP_HAVE_MODULE_GUI #if defined(VISP_HAVE_X11) display = new vpDisplayX; @@ -194,7 +194,7 @@ void *laser_display_and_save_loop(void *) // std::endl; } delete display; - return NULL; + return nullptr; } void *laser_acq_loop(void *) @@ -223,7 +223,7 @@ void *laser_acq_loop(void *) std::cout << "laser acq time: " << vpTime::measureTimeMs() - t1 << std::endl; } - return NULL; + return nullptr; } void *camera_acq_and_display_loop(void *) @@ -235,7 +235,7 @@ void *camera_acq_and_display_loop(void *) // If no camera found return if (g.getNumCameras() == 0) - return NULL; + return nullptr; // g.setVideoMode(vp1394TwoGrabber::vpVIDEO_MODE_640x480_MONO8); // g.setFramerate(vp1394TwoGrabber::vpFRAMERATE_60); @@ -245,7 +245,7 @@ void *camera_acq_and_display_loop(void *) g.acquire(I); // Acquire an image I.quarterSizeImage(Q); - vpDisplay *display = NULL; + vpDisplay *display = nullptr; #ifdef VISP_HAVE_MODULE_GUI #if defined(VISP_HAVE_X11) display = new vpDisplayX; @@ -292,7 +292,7 @@ void *camera_acq_and_display_loop(void *) } catch (...) { } #endif - return NULL; + return nullptr; } int main(int argc, const char **argv) @@ -312,18 +312,18 @@ int main(int argc, const char **argv) // Parse the command line to set the variables vpParseArgv::vpArgvInfo argTable[] = { - {"-layer", vpParseArgv::ARGV_INT, (char *)NULL, (char *)&layerToDisplay, + {"-layer", vpParseArgv::ARGV_INT, (char *)nullptr, (char *)&layerToDisplay, "The layer to display:\n" "\t\t. 0x1 for layer 1.\n" "\t\t. 0x2 for layer 2.\n" "\t\t. 0x4 for layer 3.\n" "\t\t. 0x8 for layer 4.\n" "\t\tTo display all the layers you should set 0xF value."}, - {"-save", vpParseArgv::ARGV_INT, (char *)NULL, (char *)&save, "Turn to 1 in order to save data."}, - {"-h", vpParseArgv::ARGV_HELP, (char *)NULL, (char *)NULL, + {"-save", vpParseArgv::ARGV_INT, (char *)nullptr, (char *)&save, "Turn to 1 in order to save data."}, + {"-h", vpParseArgv::ARGV_HELP, (char *)nullptr, (char *)nullptr, "Display one or more measured layers form a Sick LD-MRS laser " "scanner."}, - {(char *)NULL, vpParseArgv::ARGV_END, (char *)NULL, (char *)NULL, (char *)NULL}}; + {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; // Read the command line options if (vpParseArgv::parse(&argc, argv, argTable, @@ -337,9 +337,9 @@ int main(int argc, const char **argv) pthread_t thread_camera_acq; pthread_t thread_laser_acq; pthread_t thread_laser_display; - pthread_create(&thread_camera_acq, NULL, &camera_acq_and_display_loop, NULL); - pthread_create(&thread_laser_acq, NULL, &laser_acq_loop, NULL); - pthread_create(&thread_laser_display, NULL, &laser_display_and_save_loop, NULL); + pthread_create(&thread_camera_acq, nullptr, &camera_acq_and_display_loop, nullptr); + pthread_create(&thread_laser_acq, nullptr, &laser_acq_loop, nullptr); + pthread_create(&thread_laser_display, nullptr, &laser_display_and_save_loop, nullptr); pthread_join(thread_camera_acq, 0); pthread_join(thread_laser_acq, 0); pthread_join(thread_laser_display, 0); diff --git a/example/device/light/ringLight.cpp b/example/device/light/ringLight.cpp index 955a58ace0..a0c908af88 100644 --- a/example/device/light/ringLight.cpp +++ b/example/device/light/ringLight.cpp @@ -141,7 +141,7 @@ bool getOptions(int argc, const char **argv, bool &on, int &nsec, double &nmsec) nmsec = atof(optarg); break; case 'h': - usage(argv[0], NULL, nsec, nmsec); + usage(argv[0], nullptr, nsec, nmsec); return false; break; @@ -154,7 +154,7 @@ bool getOptions(int argc, const char **argv, bool &on, int &nsec, double &nmsec) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, nsec, nmsec); + usage(argv[0], nullptr, nsec, nmsec); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; diff --git a/example/direct-visual-servoing/photometricVisualServoing.cpp b/example/direct-visual-servoing/photometricVisualServoing.cpp index 6e2471f0a6..3d64ef22be 100644 --- a/example/direct-visual-servoing/photometricVisualServoing.cpp +++ b/example/direct-visual-servoing/photometricVisualServoing.cpp @@ -149,7 +149,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all niter = atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, niter); + usage(argv[0], nullptr, ipath, niter); return false; default: @@ -160,7 +160,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, niter); + usage(argv[0], nullptr, ipath, niter); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -211,7 +211,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_niter); + usage(argv[0], nullptr, ipath, opt_niter); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp b/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp index 31e590054c..19ead6ef91 100644 --- a/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp +++ b/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp @@ -150,7 +150,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all niter = atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, niter); + usage(argv[0], nullptr, ipath, niter); return false; default: @@ -161,7 +161,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, niter); + usage(argv[0], nullptr, ipath, niter); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -212,7 +212,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_niter); + usage(argv[0], nullptr, ipath, opt_niter); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/homography/homographyHLM2DObject.cpp b/example/homography/homographyHLM2DObject.cpp index 8535960ad2..ef357b8043 100644 --- a/example/homography/homographyHLM2DObject.cpp +++ b/example/homography/homographyHLM2DObject.cpp @@ -115,7 +115,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -128,7 +128,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/homography/homographyHLM3DObject.cpp b/example/homography/homographyHLM3DObject.cpp index 9ead514611..ffafeab16a 100644 --- a/example/homography/homographyHLM3DObject.cpp +++ b/example/homography/homographyHLM3DObject.cpp @@ -116,7 +116,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -129,7 +129,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/homography/homographyHartleyDLT2DObject.cpp b/example/homography/homographyHartleyDLT2DObject.cpp index 74d5f5102d..cce2a041ba 100644 --- a/example/homography/homographyHartleyDLT2DObject.cpp +++ b/example/homography/homographyHartleyDLT2DObject.cpp @@ -115,7 +115,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -128,7 +128,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/homography/homographyRansac2DObject.cpp b/example/homography/homographyRansac2DObject.cpp index c8dda44226..184f1dcf00 100644 --- a/example/homography/homographyRansac2DObject.cpp +++ b/example/homography/homographyRansac2DObject.cpp @@ -114,7 +114,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -127,7 +127,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/image/imageDiskRW.cpp b/example/image/imageDiskRW.cpp index 10af918a45..c4f39f762a 100644 --- a/example/image/imageDiskRW.cpp +++ b/example/image/imageDiskRW.cpp @@ -134,7 +134,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -215,7 +215,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(dirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << dirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -236,7 +236,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/manual/ogre/HelloWorldOgreAdvanced.cpp b/example/manual/ogre/HelloWorldOgreAdvanced.cpp index d301bda557..2ca3f16904 100644 --- a/example/manual/ogre/HelloWorldOgreAdvanced.cpp +++ b/example/manual/ogre/HelloWorldOgreAdvanced.cpp @@ -67,7 +67,7 @@ class vpAROgreAdvanced : public vpAROgre unsigned int height = 480) : vpAROgre(cam, width, height) { - mAnimationState = NULL; + mAnimationState = nullptr; } protected: diff --git a/example/manual/simulation/manSimu4Dots.cpp b/example/manual/simulation/manSimu4Dots.cpp index 6e0fdd876f..b2547edbfb 100644 --- a/example/manual/simulation/manSimu4Dots.cpp +++ b/example/manual/simulation/manSimu4Dots.cpp @@ -236,7 +236,7 @@ static void *mainLoop(void *_simu) task.print(); simu->closeMainApplication(); - void *a = NULL; + void *a = nullptr; return a; } diff --git a/example/manual/simulation/manSimu4Points.cpp b/example/manual/simulation/manSimu4Points.cpp index 8486eecda9..99502c3c62 100644 --- a/example/manual/simulation/manSimu4Points.cpp +++ b/example/manual/simulation/manSimu4Points.cpp @@ -187,7 +187,7 @@ static void *mainLoop(void *_simu) } simu->closeMainApplication(); - void *a = NULL; + void *a = nullptr; return a; // return (void *); } diff --git a/example/math/BSpline.cpp b/example/math/BSpline.cpp index 5056dfded9..b3507584fb 100644 --- a/example/math/BSpline.cpp +++ b/example/math/BSpline.cpp @@ -133,7 +133,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -146,7 +146,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -253,13 +253,13 @@ int main(int argc, const char **argv) unsigned int i = bSpline.findSpan(5 / 2.0); std::cout << "The knot interval number for the value u = 5/2 is : " << i << std::endl; - vpBasisFunction *N = NULL; + vpBasisFunction *N = nullptr; N = bSpline.computeBasisFuns(5 / 2.0); std::cout << "The nonvanishing basis functions N(u=5/2) are :" << std::endl; for (unsigned int j = 0; j < bSpline.get_p() + 1; j++) std::cout << N[j].value << std::endl; - vpBasisFunction **N2 = NULL; + vpBasisFunction **N2 = nullptr; N2 = bSpline.computeDersBasisFuns(5 / 2.0, 2); std::cout << "The first derivatives of the basis functions N'(u=5/2) are :" << std::endl; for (unsigned int j = 0; j < bSpline.get_p() + 1; j++) @@ -283,9 +283,9 @@ int main(int argc, const char **argv) vpDisplay::getClick(I); } - if (N != NULL) + if (N != nullptr) delete [] N; - if (N2 != NULL) { + if (N2 != nullptr) { for (unsigned int j = 0; j <= 2; j++) delete [] N2[j]; delete [] N2; diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index 116b570804..26324c8b1e 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -120,7 +120,7 @@ int main(int argc, char **argv) const double eps = 1e-2; #ifdef VISP_HAVE_DISPLAY - QPlot *plot = NULL; + QPlot *plot = nullptr; if (opt_display) plot = new QPlot(1, total, { "time to solveQP", "warm start" }); #endif diff --git a/example/math/quadprog_eq.cpp b/example/math/quadprog_eq.cpp index 49c20b23de..079f34a77c 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -123,7 +123,7 @@ int main(int argc, char **argv) const double eps = 1e-2; #ifdef VISP_HAVE_DISPLAY - QPlot *plot = NULL; + QPlot *plot = nullptr; if (opt_display) plot = new QPlot(2, total, { "only equalities", "pre-solving", "equalities + inequalities", "pre-solving / warm start" }); diff --git a/example/moments/image/servoMomentImage.cpp b/example/moments/image/servoMomentImage.cpp index 17bed69c0f..bd3c7045ae 100644 --- a/example/moments/image/servoMomentImage.cpp +++ b/example/moments/image/servoMomentImage.cpp @@ -94,7 +94,7 @@ class servoMoment : m_width(640), m_height(480), m_cMo(), m_cdMo(), m_robot(), m_Iint(m_height, m_width, 0), m_task(), m_cam(), m_error(0), m_imsim(), m_cur_img(m_height, m_width, 0), m_src_img(m_height, m_width, 0), m_dst_img(m_height, m_width, 0), m_start_img(m_height, m_width, 0), m_interaction_type(), m_src(6), m_dst(6), - m_moments(NULL), m_momentsDes(NULL), m_featureMoments(NULL), m_featureMomentsDes(NULL), m_displayInt(NULL) + m_moments(nullptr), m_momentsDes(nullptr), m_featureMoments(nullptr), m_featureMomentsDes(nullptr), m_displayInt(nullptr) { } ~servoMoment() { diff --git a/example/moments/points/servoMomentPoints.cpp b/example/moments/points/servoMomentPoints.cpp index 34dc30ef5e..53c0f5782c 100644 --- a/example/moments/points/servoMomentPoints.cpp +++ b/example/moments/points/servoMomentPoints.cpp @@ -91,8 +91,8 @@ class servoMoment public: servoMoment() : m_width(640), m_height(480), m_cMo(), m_cdMo(), m_robot(false), m_Iint(m_height, m_width, 255), m_task(), m_cam(), - m_error(0), m_imsim(), m_interaction_type(), m_src(6), m_dst(6), m_moments(NULL), m_momentsDes(NULL), - m_featureMoments(NULL), m_featureMomentsDes(NULL), m_displayInt(NULL) + m_error(0), m_imsim(), m_interaction_type(), m_src(6), m_dst(6), m_moments(nullptr), m_momentsDes(nullptr), + m_featureMoments(nullptr), m_featureMomentsDes(nullptr), m_displayInt(nullptr) { } ~servoMoment() { diff --git a/example/moments/polygon/servoMomentPolygon.cpp b/example/moments/polygon/servoMomentPolygon.cpp index f1637b6246..4134c33caa 100644 --- a/example/moments/polygon/servoMomentPolygon.cpp +++ b/example/moments/polygon/servoMomentPolygon.cpp @@ -90,8 +90,8 @@ class servoMoment public: servoMoment() : m_width(640), m_height(480), m_cMo(), m_cdMo(), m_robot(false), m_Iint(m_height, m_width, 255), m_task(), m_cam(), - m_error(0), m_imsim(), m_interaction_type(), m_src(6), m_dst(6), m_moments(NULL), m_momentsDes(NULL), - m_featureMoments(NULL), m_featureMomentsDes(NULL), m_displayInt(NULL) + m_error(0), m_imsim(), m_interaction_type(), m_src(6), m_dst(6), m_moments(nullptr), m_momentsDes(nullptr), + m_featureMoments(nullptr), m_featureMomentsDes(nullptr), m_displayInt(nullptr) { } ~servoMoment() { diff --git a/example/ogre-simulator/AROgre.cpp b/example/ogre-simulator/AROgre.cpp index 2ba72b250c..05b4b36f24 100644 --- a/example/ogre-simulator/AROgre.cpp +++ b/example/ogre-simulator/AROgre.cpp @@ -161,7 +161,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp ppath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); return false; break; @@ -174,7 +174,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -190,7 +190,7 @@ class vpAROgreExample : public vpAROgre public: // The constructor doesn't change here vpAROgreExample(const vpCameraParameters &cam = vpCameraParameters(), unsigned int width = 640, - unsigned int height = 480, const char *resourcePath = NULL) + unsigned int height = 480, const char *resourcePath = nullptr) : vpAROgre(cam, width, height) { // Direction vectors @@ -198,8 +198,8 @@ class vpAROgreExample : public vpAROgre mResourcePath = resourcePath; std::cout << "mResourcePath: " << mResourcePath << std::endl; vecDevant = Ogre::Vector3(0, -1, 0); - robot = NULL; - mAnimationState = NULL; + robot = nullptr; + mAnimationState = nullptr; } protected: @@ -572,7 +572,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath); + usage(argv[0], nullptr, ipath, opt_ppath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/ogre-simulator/AROgreBasic.cpp b/example/ogre-simulator/AROgreBasic.cpp index 17ecd07bbe..7f740ac9c0 100644 --- a/example/ogre-simulator/AROgreBasic.cpp +++ b/example/ogre-simulator/AROgreBasic.cpp @@ -159,7 +159,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp ppath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); return false; break; @@ -172,7 +172,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -436,7 +436,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath); + usage(argv[0], nullptr, ipath, opt_ppath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/parse-argv/parse-argv1.cpp b/example/parse-argv/parse-argv1.cpp index d57e596612..0764f3fa9b 100644 --- a/example/parse-argv/parse-argv1.cpp +++ b/example/parse-argv/parse-argv1.cpp @@ -129,7 +129,7 @@ bool getOptions(int argc, const char **argv, int &i_val, float &f_val, double &d i_val = atoi(optarg_); break; case 'h': - usage(argv[0], NULL, i_val, f_val, d_val); + usage(argv[0], nullptr, i_val, f_val, d_val); return false; break; @@ -142,7 +142,7 @@ bool getOptions(int argc, const char **argv, int &i_val, float &f_val, double &d if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, i_val, f_val, d_val); + usage(argv[0], nullptr, i_val, f_val, d_val); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/parse-argv/parse-argv2.cpp b/example/parse-argv/parse-argv2.cpp index 07d2e414d7..bf8534c8a0 100644 --- a/example/parse-argv/parse-argv2.cpp +++ b/example/parse-argv/parse-argv2.cpp @@ -64,17 +64,17 @@ int main(int argc, const char **argv) long long_val = 33333333; float float_val = 3.14f; double double_val = 3.1415; - char *string_val = NULL; + char *string_val = nullptr; vpParseArgv::vpArgvInfo argTable[] = { {"-bool", vpParseArgv::ARGV_CONSTANT_BOOL, 0, (char *)&bool_val, "Bool enabled."}, - {"-integer", vpParseArgv::ARGV_INT, (char *)NULL, (char *)&int_val, "An integer value."}, - {"-long", vpParseArgv::ARGV_LONG, (char *)NULL, (char *)&long_val, "A long value."}, - {"-float", vpParseArgv::ARGV_FLOAT, (char *)NULL, (char *)&float_val, "A float value."}, - {"-double", vpParseArgv::ARGV_DOUBLE, (char *)NULL, (char *)&double_val, "A double value."}, - {"-string", vpParseArgv::ARGV_STRING, (char *)NULL, (char *)&string_val, "A chain value."}, - {"-h", vpParseArgv::ARGV_HELP, (char *)NULL, (char *)NULL, "Print the help."}, - {(char *)NULL, vpParseArgv::ARGV_END, (char *)NULL, (char *)NULL, (char *)NULL}}; + {"-integer", vpParseArgv::ARGV_INT, (char *)nullptr, (char *)&int_val, "An integer value."}, + {"-long", vpParseArgv::ARGV_LONG, (char *)nullptr, (char *)&long_val, "A long value."}, + {"-float", vpParseArgv::ARGV_FLOAT, (char *)nullptr, (char *)&float_val, "A float value."}, + {"-double", vpParseArgv::ARGV_DOUBLE, (char *)nullptr, (char *)&double_val, "A double value."}, + {"-string", vpParseArgv::ARGV_STRING, (char *)nullptr, (char *)&string_val, "A chain value."}, + {"-h", vpParseArgv::ARGV_HELP, (char *)nullptr, (char *)nullptr, "Print the help."}, + {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; // Read the command line options if (vpParseArgv::parse(&argc, argv, argTable, vpParseArgv::ARGV_NO_DEFAULTS)) { @@ -87,7 +87,7 @@ int main(int argc, const char **argv) cout << " Long value: " << long_val << endl; cout << " Float value: " << float_val << endl; cout << " Double value: " << double_val << endl; - if (string_val != NULL) + if (string_val != nullptr) cout << " String value: " << string_val << endl; else cout << " String value: \"\"" << endl << endl; diff --git a/example/pose-estimation/poseVirtualVS.cpp b/example/pose-estimation/poseVirtualVS.cpp index 728e2156f9..74060d07fc 100644 --- a/example/pose-estimation/poseVirtualVS.cpp +++ b/example/pose-estimation/poseVirtualVS.cpp @@ -203,7 +203,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp step = (unsigned)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); return false; break; @@ -216,7 +216,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -286,7 +286,7 @@ int main(int argc, const char **argv) } // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp index ba21c02177..649961326d 100644 --- a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp @@ -148,7 +148,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -161,7 +161,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp index 33f398967c..6af43f9c55 100644 --- a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp @@ -116,7 +116,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -127,7 +127,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp index 461bb81b8a..b68df9d2ee 100644 --- a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp @@ -140,7 +140,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -151,7 +151,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp index 0ecdff8951..d5b615f6f2 100644 --- a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp @@ -117,7 +117,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -128,7 +128,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp index 12cee6a614..37cb1dfb9c 100644 --- a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp @@ -132,7 +132,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -143,7 +143,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp index 11dcdcd0a5..2ab28359fc 100644 --- a/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp @@ -115,7 +115,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -126,7 +126,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp index 1c0137c4ff..e8679dc4ee 100644 --- a/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp @@ -139,7 +139,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -150,7 +150,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp index b218f53e9d..303387dd4a 100644 --- a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp index cd620bf763..7599c18c77 100644 --- a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp +++ b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp @@ -145,7 +145,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, new_proj_operator = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -156,7 +156,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp index 44d4f0ad66..8f2fd160e1 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp @@ -116,7 +116,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -127,7 +127,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp index 1a5fb28ab9..ed0597d062 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp @@ -143,7 +143,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -154,7 +154,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp index 8feb9ac384..7612b05139 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp @@ -145,7 +145,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -156,7 +156,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp index 12522e583f..7b5df1375c 100644 --- a/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp @@ -135,7 +135,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -146,7 +146,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp index 71fd7702a0..d1c5358b75 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp @@ -106,7 +106,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -117,7 +117,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp index 60b02f9a8b..a4735b704b 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp @@ -114,7 +114,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -125,7 +125,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp index 68734766bc..bb4b90bfd2 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp @@ -113,7 +113,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -124,7 +124,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp index 195ac04bd2..a2c831ebb4 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp @@ -113,7 +113,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -124,7 +124,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp index 4ce3cba734..2e3b97ae49 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp @@ -109,7 +109,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp index fb6fb34024..656e9e0274 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp @@ -109,7 +109,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp index 04af2bdf0c..fb36403ea4 100644 --- a/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp @@ -108,7 +108,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -119,7 +119,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp index 0f24abc76d..d0fda0cc78 100644 --- a/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp @@ -108,7 +108,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -119,7 +119,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp index 2ff819188c..c0d1dffc75 100644 --- a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp @@ -128,7 +128,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -139,7 +139,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp index f138daa936..99b0da9da4 100644 --- a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp +++ b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp @@ -139,7 +139,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, new_proj_operator = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -150,7 +150,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp index 55edc655a7..06defae5d3 100644 --- a/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp b/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp index 89fcf46842..ae54cecbb5 100644 --- a/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp @@ -108,7 +108,7 @@ bool getOptions(int argc, const char **argv) switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; default: @@ -119,7 +119,7 @@ bool getOptions(int argc, const char **argv) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp index f91fa8bc6f..b99dc47015 100644 --- a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp @@ -148,7 +148,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -161,7 +161,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/servo-afma4/moveAfma4.cpp b/example/servo-afma4/moveAfma4.cpp index ad8444e67e..5594c45864 100644 --- a/example/servo-afma4/moveAfma4.cpp +++ b/example/servo-afma4/moveAfma4.cpp @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv, bool &control) control = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -133,7 +133,7 @@ bool getOptions(int argc, const char **argv, bool &control) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; diff --git a/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp b/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp index d2b3430425..b7a52a5797 100644 --- a/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp +++ b/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp @@ -154,7 +154,7 @@ bool getOptions(int argc, const char **argv, KalmanType &kalman, bool &doAdaptat lambda.initFromConstant(atof(optarg)); break; case 'h': - usage(argv[0], NULL, kalman); + usage(argv[0], nullptr, kalman); return false; break; @@ -167,7 +167,7 @@ bool getOptions(int argc, const char **argv, KalmanType &kalman, bool &doAdaptat if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, kalman); + usage(argv[0], nullptr, kalman); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; diff --git a/example/servo-biclops/moveBiclops.cpp b/example/servo-biclops/moveBiclops.cpp index d1ab30ce44..55cce1c1a8 100644 --- a/example/servo-biclops/moveBiclops.cpp +++ b/example/servo-biclops/moveBiclops.cpp @@ -102,7 +102,7 @@ bool getOptions(int argc, const char **argv, std::string &conf) conf = optarg_; break; case 'h': - usage(argv[0], NULL, conf); + usage(argv[0], nullptr, conf); return false; break; @@ -115,7 +115,7 @@ bool getOptions(int argc, const char **argv, std::string &conf) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, conf); + usage(argv[0], nullptr, conf); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp b/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp index dd63b1dba8..c969ba5a5a 100644 --- a/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp +++ b/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv, std::string &conf) conf = optarg_; break; case 'h': - usage(argv[0], NULL, conf); + usage(argv[0], nullptr, conf); return false; break; @@ -133,7 +133,7 @@ bool getOptions(int argc, const char **argv, std::string &conf) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, conf); + usage(argv[0], nullptr, conf); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/example/servo-pioneer/sonarPioneerReader.cpp b/example/servo-pioneer/sonarPioneerReader.cpp index 77e0e78c27..048b9f610a 100644 --- a/example/servo-pioneer/sonarPioneerReader.cpp +++ b/example/servo-pioneer/sonarPioneerReader.cpp @@ -81,11 +81,11 @@ void sonarPrinter(void) ArPose *pose; sd = (ArSonarDevice *)robot->findRangeDevice("sonar"); - if (sd != NULL) + if (sd != nullptr) { sd->lockDevice(); readings = sd->getCurrentBuffer(); - if (readings != NULL) + if (readings != nullptr) { for (it = readings->begin(); it != readings->end(); ++it) { @@ -158,7 +158,7 @@ void sonarPrinter(void) ArSensorReading *reading; for (int sensor = 0; sensor < robot->getNumSonar(); sensor++) { reading = robot->getSonarReading(sensor); - if (reading != NULL) { + if (reading != nullptr) { angle = reading->getSensorTh(); range = reading->getRange(); double sx = reading->getSensorX(); // position of the sensor in the robot frame @@ -328,7 +328,7 @@ int main(int argc, char **argv) #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) if (isInitialized) { - if (d != NULL) + if (d != nullptr) delete d; } #endif diff --git a/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp b/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp index c02068f252..0cebdd1212 100644 --- a/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp +++ b/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp @@ -236,7 +236,7 @@ int main() double t_0, t_1, Tv; vpColVector err(2), err_1(2); vpColVector dedt_filt(2), dedt_mes(2); - dc1394video_frame_t *frame = NULL; + dc1394video_frame_t *frame = nullptr; t_1 = vpTime::measureTimeMs(); diff --git a/example/tools/histogram.cpp b/example/tools/histogram.cpp index 389a2d69a9..22b54ee5ba 100644 --- a/example/tools/histogram.cpp +++ b/example/tools/histogram.cpp @@ -137,7 +137,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -150,7 +150,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -208,7 +208,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(dirname); } catch (...) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << dirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; @@ -229,7 +229,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opath, username); + usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tools/parallelPort.cpp b/example/tools/parallelPort.cpp index 6f154bd1cc..d3b55d54e0 100644 --- a/example/tools/parallelPort.cpp +++ b/example/tools/parallelPort.cpp @@ -123,7 +123,7 @@ bool getOptions(int argc, const char **argv, unsigned char &data) break; } case 'h': - usage(argv[0], NULL, data); + usage(argv[0], nullptr, data); return false; break; @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, unsigned char &data) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, data); + usage(argv[0], nullptr, data); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg << std::endl << std::endl; return false; diff --git a/example/tracking/mbtEdgeKltTracking.cpp b/example/tracking/mbtEdgeKltTracking.cpp index 747b9ee928..1cee25a362 100644 --- a/example/tracking/mbtEdgeKltTracking.cpp +++ b/example/tracking/mbtEdgeKltTracking.cpp @@ -206,7 +206,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co projectionError = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -219,7 +219,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -276,7 +276,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/mbtEdgeTracking.cpp b/example/tracking/mbtEdgeTracking.cpp index 136ffc7aa8..5381e916c9 100644 --- a/example/tracking/mbtEdgeTracking.cpp +++ b/example/tracking/mbtEdgeTracking.cpp @@ -206,7 +206,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co projectionError = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -219,7 +219,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -276,7 +276,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/mbtGenericTracking.cpp b/example/tracking/mbtGenericTracking.cpp index 007fe75c44..5249b137da 100644 --- a/example/tracking/mbtGenericTracking.cpp +++ b/example/tracking/mbtGenericTracking.cpp @@ -214,7 +214,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co trackerType = atoi(optarg_); break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -227,7 +227,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -283,7 +283,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -656,7 +656,7 @@ int main(int argc, const char **argv) reader.close(); delete tracker; - tracker = NULL; + tracker = nullptr; return EXIT_SUCCESS; } diff --git a/example/tracking/mbtGenericTracking2.cpp b/example/tracking/mbtGenericTracking2.cpp index 050dc6066d..357dc9cf56 100644 --- a/example/tracking/mbtGenericTracking2.cpp +++ b/example/tracking/mbtGenericTracking2.cpp @@ -214,7 +214,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co trackerType = atoi(optarg_); break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -227,7 +227,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -283,7 +283,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -743,7 +743,7 @@ int main(int argc, const char **argv) reader.close(); delete tracker; - tracker = NULL; + tracker = nullptr; return EXIT_SUCCESS; } diff --git a/example/tracking/mbtGenericTrackingDepth.cpp b/example/tracking/mbtGenericTrackingDepth.cpp index 32dbb3cd4e..bad1cf3f8c 100644 --- a/example/tracking/mbtGenericTrackingDepth.cpp +++ b/example/tracking/mbtGenericTrackingDepth.cpp @@ -214,7 +214,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co lastFrame = atoi(optarg_); break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -227,7 +227,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -483,7 +483,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -825,7 +825,7 @@ int main(int argc, const char **argv) } delete tracker; - tracker = NULL; + tracker = nullptr; return EXIT_SUCCESS; } diff --git a/example/tracking/mbtGenericTrackingDepthOnly.cpp b/example/tracking/mbtGenericTrackingDepthOnly.cpp index 45d5804804..36228e84ca 100644 --- a/example/tracking/mbtGenericTrackingDepthOnly.cpp +++ b/example/tracking/mbtGenericTrackingDepthOnly.cpp @@ -201,7 +201,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; default: @@ -213,7 +213,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -445,7 +445,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -769,7 +769,7 @@ int main(int argc, const char **argv) } delete tracker; - tracker = NULL; + tracker = nullptr; return EXIT_SUCCESS; } catch (const vpException &e) { diff --git a/example/tracking/mbtKltTracking.cpp b/example/tracking/mbtKltTracking.cpp index cc9cc9e2df..8c6ba3f3d7 100644 --- a/example/tracking/mbtKltTracking.cpp +++ b/example/tracking/mbtKltTracking.cpp @@ -190,7 +190,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co computeCovariance = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -203,7 +203,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &co if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -258,7 +258,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/templateTracker.cpp b/example/tracking/templateTracker.cpp index 0579e517e2..2fec809a78 100644 --- a/example/tracking/templateTracker.cpp +++ b/example/tracking/templateTracker.cpp @@ -260,7 +260,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all display = false; break; case 'h': - usage(argv[0], NULL, warp_type, tracker_type, last_frame, threshold_residual); + usage(argv[0], nullptr, warp_type, tracker_type, last_frame, threshold_residual); return false; break; case 'i': @@ -296,13 +296,13 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all } if (warp_type >= WARP_LAST) { - usage(argv[0], NULL, warp_type, tracker_type, last_frame, threshold_residual); + usage(argv[0], nullptr, warp_type, tracker_type, last_frame, threshold_residual); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument -w with \"warp type\"=" << (int)warp_type << std::endl << std::endl; return false; } if (tracker_type >= TRACKER_LAST) { - usage(argv[0], NULL, warp_type, tracker_type, last_frame, threshold_residual); + usage(argv[0], nullptr, warp_type, tracker_type, last_frame, threshold_residual); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument -t with \"tracker type\"=" << (int)tracker_type << std::endl << std::endl; @@ -310,7 +310,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all } if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, warp_type, tracker_type, last_frame, threshold_residual); + usage(argv[0], nullptr, warp_type, tracker_type, last_frame, threshold_residual); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -374,7 +374,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, opt_warp_type, opt_tracker_type, opt_last_frame, opt_threshold_residual); + usage(argv[0], nullptr, opt_warp_type, opt_tracker_type, opt_last_frame, opt_threshold_residual); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -408,7 +408,7 @@ int main(int argc, const char **argv) } reader.acquire(I); - vpDisplay *display = NULL; + vpDisplay *display = nullptr; if (opt_display) { // initialise a display #if defined(VISP_HAVE_X11) @@ -431,7 +431,7 @@ int main(int argc, const char **argv) vpDisplay::flush(I); } - vpTemplateTrackerWarp *warp = NULL; + vpTemplateTrackerWarp *warp = nullptr; switch (opt_warp_type) { case WARP_AFFINE: warp = new vpTemplateTrackerWarpAffine; @@ -457,7 +457,7 @@ int main(int argc, const char **argv) return EXIT_FAILURE; } - vpTemplateTracker *tracker = NULL; + vpTemplateTracker *tracker = nullptr; switch (opt_tracker_type) { case TRACKER_SSD_ESM: tracker = new vpTemplateTrackerSSDESM(warp); diff --git a/example/tracking/trackDot.cpp b/example/tracking/trackDot.cpp index 68223d8613..3e5d59141b 100644 --- a/example/tracking/trackDot.cpp +++ b/example/tracking/trackDot.cpp @@ -188,7 +188,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp step = (unsigned)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); return false; break; @@ -201,7 +201,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -262,7 +262,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/trackDot2.cpp b/example/tracking/trackDot2.cpp index 086f50ec9b..d5172f9b09 100644 --- a/example/tracking/trackDot2.cpp +++ b/example/tracking/trackDot2.cpp @@ -187,7 +187,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp step = (unsigned)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); return false; break; @@ -200,7 +200,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -261,7 +261,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/trackDot2WithAutoDetection.cpp b/example/tracking/trackDot2WithAutoDetection.cpp index ae32188fe4..a36f81e180 100644 --- a/example/tracking/trackDot2WithAutoDetection.cpp +++ b/example/tracking/trackDot2WithAutoDetection.cpp @@ -229,7 +229,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp ellipsoidShapePrecision = atof(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step, sizePrecision, grayLevelPrecision, + usage(argv[0], nullptr, ipath, ppath, first, last, step, sizePrecision, grayLevelPrecision, ellipsoidShapePrecision); return false; break; @@ -244,7 +244,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step, sizePrecision, grayLevelPrecision, + usage(argv[0], nullptr, ipath, ppath, first, last, step, sizePrecision, grayLevelPrecision, ellipsoidShapePrecision); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; @@ -309,7 +309,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_sizePrecision, + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_sizePrecision, opt_grayLevelPrecision, opt_ellipsoidShapePrecision); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl diff --git a/example/tracking/trackKltOpencv.cpp b/example/tracking/trackKltOpencv.cpp index 763df34d01..1047b4d5bc 100644 --- a/example/tracking/trackKltOpencv.cpp +++ b/example/tracking/trackKltOpencv.cpp @@ -195,7 +195,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp step = (unsigned)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); return false; break; @@ -208,7 +208,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -269,7 +269,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/trackMeCircle.cpp b/example/tracking/trackMeCircle.cpp index 753623a141..26e787f8ca 100644 --- a/example/tracking/trackMeCircle.cpp +++ b/example/tracking/trackMeCircle.cpp @@ -150,7 +150,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all ipath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -163,7 +163,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -220,7 +220,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/trackMeEllipse.cpp b/example/tracking/trackMeEllipse.cpp index c3aec3bd83..3df632b198 100644 --- a/example/tracking/trackMeEllipse.cpp +++ b/example/tracking/trackMeEllipse.cpp @@ -263,7 +263,7 @@ bool getOptions(int argc, const char **argv, std::string &video_in_ipath, std::s verbose = true; break; case 'h': - usage(argv[0], NULL, video_in_ipath, video_in_ppath, video_in_first, video_in_last, video_in_step, me_range, me_sample_step, me_threshold); + usage(argv[0], nullptr, video_in_ipath, video_in_ppath, video_in_first, video_in_last, video_in_step, me_range, me_sample_step, me_threshold); return false; break; @@ -276,7 +276,7 @@ bool getOptions(int argc, const char **argv, std::string &video_in_ipath, std::s if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, video_in_ipath, video_in_ppath, video_in_first, video_in_last, video_in_step, me_range, me_sample_step, me_threshold); + usage(argv[0], nullptr, video_in_ipath, video_in_ppath, video_in_first, video_in_last, video_in_step, me_range, me_sample_step, me_threshold); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -313,7 +313,7 @@ int main(int argc, const char **argv) // read on the disk vpImage I; - vpDisplay *display = NULL; + vpDisplay *display = nullptr; try { // Get the visp-images-data package path or VISP_INPUT_IMAGE_PATH @@ -348,7 +348,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_me_range, opt_me_sample_step, opt_me_threshold); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_me_range, opt_me_sample_step, opt_me_threshold); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -418,7 +418,7 @@ int main(int argc, const char **argv) vpDisplay::flush(I); } - vpVideoWriter *writer = NULL; + vpVideoWriter *writer = nullptr; vpImage O; if (!opt_save.empty()) { writer = new vpVideoWriter(); diff --git a/example/tracking/trackMeLine.cpp b/example/tracking/trackMeLine.cpp index 18a47623d1..e578375201 100644 --- a/example/tracking/trackMeLine.cpp +++ b/example/tracking/trackMeLine.cpp @@ -193,7 +193,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp step = (unsigned)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); return false; break; @@ -206,7 +206,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step); + usage(argv[0], nullptr, ipath, ppath, first, last, step); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -268,7 +268,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/tracking/trackMeNurbs.cpp b/example/tracking/trackMeNurbs.cpp index 3987e64b4d..9b0efefe0b 100644 --- a/example/tracking/trackMeNurbs.cpp +++ b/example/tracking/trackMeNurbs.cpp @@ -153,7 +153,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all ipath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -166,7 +166,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -221,7 +221,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/video/imageSequenceReader.cpp b/example/video/imageSequenceReader.cpp index eb0364a617..c697273777 100644 --- a/example/video/imageSequenceReader.cpp +++ b/example/video/imageSequenceReader.cpp @@ -162,7 +162,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp first = atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); return false; break; @@ -175,7 +175,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -239,7 +239,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath); + usage(argv[0], nullptr, ipath, opt_ppath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/video/videoReader.cpp b/example/video/videoReader.cpp index 9b64d22d65..9b156b9983 100644 --- a/example/video/videoReader.cpp +++ b/example/video/videoReader.cpp @@ -149,7 +149,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp ppath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); return false; break; @@ -162,7 +162,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath); + usage(argv[0], nullptr, ipath, ppath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -219,7 +219,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath); + usage(argv[0], nullptr, ipath, opt_ppath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/example/wireframe-simulator/wireframeSimulator.cpp b/example/wireframe-simulator/wireframeSimulator.cpp index cdaacf1a80..8638b2061c 100644 --- a/example/wireframe-simulator/wireframeSimulator.cpp +++ b/example/wireframe-simulator/wireframeSimulator.cpp @@ -122,7 +122,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &click) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -135,7 +135,7 @@ bool getOptions(int argc, const char **argv, bool &display, bool &click) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/ar/include/visp3/ar/vpAROgre.h b/modules/ar/include/visp3/ar/vpAROgre.h index 8745cfc556..038db61e0d 100644 --- a/modules/ar/include/visp3/ar/vpAROgre.h +++ b/modules/ar/include/visp3/ar/vpAROgre.h @@ -280,7 +280,7 @@ class VISP_EXPORT vpAROgre : public Ogre::FrameListener, */ inline void setWindowPosition(unsigned int win_x, unsigned int win_y) { - if (mWindow == NULL) { + if (mWindow == nullptr) { throw vpException(vpException::notInitialized, "Window not initialised, cannot set its position"); } mWindow->reposition(static_cast(win_x), static_cast(win_y)); diff --git a/modules/ar/include/visp3/ar/vpSimulator.h b/modules/ar/include/visp3/ar/vpSimulator.h index a81d12ca8b..512ad4e019 100644 --- a/modules/ar/include/visp3/ar/vpSimulator.h +++ b/modules/ar/include/visp3/ar/vpSimulator.h @@ -271,7 +271,7 @@ class VISP_EXPORT vpSimulator protected: SbTime *realtime; SoOffscreenRenderer *offScreenRenderer; - void offScreenRendering(vpSimulatorViewType view = vpSimulator::EXTERNAL, int *width = NULL, int *height = NULL); + void offScreenRendering(vpSimulatorViewType view = vpSimulator::EXTERNAL, int *width = nullptr, int *height = nullptr); public: //! image of the internal view diff --git a/modules/ar/src/coin-simulator/vpAR.cpp b/modules/ar/src/coin-simulator/vpAR.cpp index 450a564666..42c8dc35fc 100644 --- a/modules/ar/src/coin-simulator/vpAR.cpp +++ b/modules/ar/src/coin-simulator/vpAR.cpp @@ -85,9 +85,9 @@ void vpAR::initInternalViewer(unsigned int width, unsigned int height, vpImageTy // no image is loaded background = false; - if (image_background != NULL) { + if (image_background != nullptr) { free(image_background); - image_background = NULL; + image_background = nullptr; } typeImage = type; diff --git a/modules/ar/src/coin-simulator/vpSimulator.cpp b/modules/ar/src/coin-simulator/vpSimulator.cpp index 13d6b9b3cd..16598e938f 100644 --- a/modules/ar/src/coin-simulator/vpSimulator.cpp +++ b/modules/ar/src/coin-simulator/vpSimulator.cpp @@ -272,53 +272,53 @@ void vpSimulator::init() external_height = 200; mainWindowInitialized = false; - internalView = NULL; - externalView = NULL; - image_background = NULL; + internalView = nullptr; + externalView = nullptr; + image_background = nullptr; zoomFactor = 1; cameraPositionInitialized = false; // write image process - realtime = NULL; - offScreenRenderer = NULL; - bufferView = NULL; + realtime = nullptr; + offScreenRenderer = nullptr; + bufferView = nullptr; get = 1; typeImage = grayImage; - mainThread = NULL; - scene = NULL; - internalRoot = NULL; - externalRoot = NULL; - internalCamera = NULL; - externalCamera = NULL; - internalCameraPosition = NULL; - extrenalCameraPosition = NULL; - internalCameraObject = NULL; + mainThread = nullptr; + scene = nullptr; + internalRoot = nullptr; + externalRoot = nullptr; + internalCamera = nullptr; + externalCamera = nullptr; + internalCameraPosition = nullptr; + extrenalCameraPosition = nullptr; + internalCameraObject = nullptr; #if defined(VISP_HAVE_SOWIN) // mainWindow = ?; #elif defined(VISP_HAVE_SOQT) - mainWindow = NULL; + mainWindow = nullptr; #elif defined(VISP_HAVE_SOXT) // mainWindow = ?; #endif } void vpSimulator::kill() { - if (internalView != NULL) { + if (internalView != nullptr) { delete internalView; - internalView = NULL; + internalView = nullptr; } - if (externalView != NULL) { + if (externalView != nullptr) { delete externalView; - externalView = NULL; + externalView = nullptr; } - if (bufferView != NULL) { + if (bufferView != nullptr) { delete[] bufferView; - bufferView = NULL; + bufferView = nullptr; } - if (image_background != NULL) { + if (image_background != nullptr) { free(image_background); - image_background = NULL; + image_background = nullptr; } } @@ -327,16 +327,16 @@ vpSimulator::vpSimulator() #if defined(VISP_HAVE_SOWIN) mainWindow(), #elif defined(VISP_HAVE_SOQT) - mainWindow(NULL), + mainWindow(nullptr), #elif defined(VISP_HAVE_SOXT) mainWindow(), #endif - mainWindowInitialized(false), typeImage(vpSimulator::grayImage), image_background(NULL), internalView(NULL), - externalView(NULL), mainThread(NULL), internal_width(0), internal_height(0), external_width(0), external_height(0), - scene(NULL), internalRoot(NULL), externalRoot(NULL), internalCamera(NULL), externalCamera(NULL), - internalCameraPosition(NULL), extrenalCameraPosition(NULL), internalCameraObject(NULL), zoomFactor(0.), - cameraPositionInitialized(false), cMf(), internalCameraParameters(), externalCameraParameters(), realtime(NULL), - offScreenRenderer(NULL), bufferView(NULL), get(0) + mainWindowInitialized(false), typeImage(vpSimulator::grayImage), image_background(nullptr), internalView(nullptr), + externalView(nullptr), mainThread(nullptr), internal_width(0), internal_height(0), external_width(0), external_height(0), + scene(nullptr), internalRoot(nullptr), externalRoot(nullptr), internalCamera(nullptr), externalCamera(nullptr), + internalCameraPosition(nullptr), extrenalCameraPosition(nullptr), internalCameraObject(nullptr), zoomFactor(0.), + cameraPositionInitialized(false), cMf(), internalCameraParameters(), externalCameraParameters(), realtime(nullptr), + offScreenRenderer(nullptr), bufferView(nullptr), get(0) { vpSimulator::init(); } @@ -391,7 +391,7 @@ void vpSimulator::initSceneGraph() this->externalRoot->addChild(cube); - if (realtime == NULL) { + if (realtime == nullptr) { SoDB::enableRealTimeSensor(FALSE); SoSceneManager::enableRealTimeUpdate(FALSE); @@ -618,12 +618,12 @@ void vpSimulator::redraw() // if (this->cameraPositionInitialized==true) { - if (this->externalView != NULL) { + if (this->externalView != nullptr) { this->externalView->render(); // call actualRedraw() // vpHomogeneousMatrix c ; // getExternalCameraPosition(c) ; } - if (this->internalView != NULL) { + if (this->internalView != nullptr) { this->moveInternalCamera(this->cMf); this->internalView->render(); // call actualRedraw() } @@ -668,7 +668,7 @@ void vpSimulator::load(const char *file_name) SoSeparator *newscene = SoDB::readAll(&input); newscene->ref(); - if (newscene == NULL) { + if (newscene == nullptr) { vpERROR_TRACE("Error while reading %s", file_name); } @@ -744,7 +744,7 @@ void vpSimulator::load(const char *iv_filename, const vpHomogeneousMatrix &fMo) } newObject = SoDB::readAll(&in); - if (NULL == newObject) { + if (nullptr == newObject) { vpERROR_TRACE("Problem reading data for file <%s>.", iv_filename); } @@ -821,7 +821,7 @@ void vpSimulator::addObject(SoSeparator *object, const vpHomogeneousMatrix &fMo, //! init the main program thread void vpSimulator::initApplication(void *(*start_routine)(void *)) { - // pthread_create (&mainThread, NULL, start_routine, (void *)this); + // pthread_create (&mainThread, nullptr, start_routine, (void *)this); mainThread = SbThread::create(start_routine, (void *)this); } @@ -843,8 +843,8 @@ void vpSimulator::initApplication(void *(*start_routine)(void *), void *data) //! should be locate at the beginning of the main program void vpSimulator::initMainApplication() { - // pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, NULL ); - // pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL); + // pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, nullptr ); + // pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, nullptr); vpTime::wait(1000); } //! performed some thread destruction in the main program thread @@ -852,7 +852,7 @@ void vpSimulator::initMainApplication() void vpSimulator::closeMainApplication() { vpViewer::exitMainLoop(); - // pthread_exit (NULL); + // pthread_exit (nullptr); } /* Initialise le SoOffScreenRenderer si necessaire, puis realise le rendu. @@ -883,7 +883,7 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * SbViewportRegion myViewPort(size); // Creation du rendu si necessaire. - if (NULL == this->offScreenRenderer) { + if (nullptr == this->offScreenRenderer) { // Init du SoOffscreenRenderer this->offScreenRenderer = new SoOffscreenRenderer(myViewPort); } else { @@ -895,7 +895,7 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * if (!this->offScreenRenderer->render(thisroot)) { vpERROR_TRACE("La scene n'a pas pu etre rendue offscreen."); delete this->offScreenRenderer; - this->offScreenRenderer = NULL; + this->offScreenRenderer = nullptr; } else { /* @@ -913,10 +913,10 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * } // exit(1) ; - if (NULL != width) { + if (nullptr != width) { *width = size[0]; } - if (NULL != height) { + if (nullptr != height) { *height = size[1]; } } diff --git a/modules/ar/src/coin-simulator/vpViewer.cpp b/modules/ar/src/coin-simulator/vpViewer.cpp index d6f5dfe6cf..084f4836bd 100644 --- a/modules/ar/src/coin-simulator/vpViewer.cpp +++ b/modules/ar/src/coin-simulator/vpViewer.cpp @@ -50,13 +50,13 @@ #if defined(VISP_HAVE_SOWIN) vpViewer::vpViewer(HWND parent, vpSimulator *_simu, vpViewerType type) - : SoWinExaminerViewer(parent, (char *)NULL, false), viewerType(type), simu(_simu) + : SoWinExaminerViewer(parent, (char *)nullptr, false), viewerType(type), simu(_simu) #elif defined(VISP_HAVE_SOQT) vpViewer::vpViewer(QWidget *parent, vpSimulator *_simu, vpViewerType type) - : SoQtExaminerViewer(parent, (char *)NULL, false), viewerType(type), simu(_simu) + : SoQtExaminerViewer(parent, (char *)nullptr, false), viewerType(type), simu(_simu) #elif defined(VISP_HAVE_SOXT) vpViewer::vpViewer(Widget parent, vpSimulator *_simu, vpViewerType type) - : SoXtExaminerViewer(parent, (char *)NULL, false), viewerType(type), simu(_simu) + : SoXtExaminerViewer(parent, (char *)nullptr, false), viewerType(type), simu(_simu) #endif { // Coin should not clear the pixel-buffer, so the background image @@ -84,7 +84,7 @@ void vpViewer::actualRedraw(void) // this should be used only with the vpAR:vpSimulator // to diplay an image background - if (simu->image_background != NULL) { + if (simu->image_background != nullptr) { glPixelStorei(GL_UNPACK_ALIGNMENT, 1); if (simu->typeImage == vpSimulator::grayImage) glDrawPixels((GLsizei)simu->getInternalWidth(), (GLsizei)simu->getInternalHeight(), (GLenum)GL_LUMINANCE, diff --git a/modules/ar/src/ogre-simulator/vpAROgre.cpp b/modules/ar/src/ogre-simulator/vpAROgre.cpp index bbd4cf952c..aa4dcf39b5 100644 --- a/modules/ar/src/ogre-simulator/vpAROgre.cpp +++ b/modules/ar/src/ogre-simulator/vpAROgre.cpp @@ -78,7 +78,7 @@ vpAROgre::vpAROgre(const vpCameraParameters &cam, unsigned int width, unsigned i mInputManager(0), mKeyboard(0), #endif keepOn(true), // When created no reason to stop displaying - mImageRGBA(), mImage(), mPixelBuffer(), mBackground(NULL), mBackgroundHeight(0), mBackgroundWidth(0), + mImageRGBA(), mImage(), mPixelBuffer(), mBackground(nullptr), mBackgroundHeight(0), mBackgroundWidth(0), mWindowHeight(height), mWindowWidth(width), windowHidden(false), mNearClipping(0.001), mFarClipping(200), mcam(cam), mshowConfigDialog(true), mOptionalResourceLocation() { @@ -246,7 +246,7 @@ void vpAROgre::init(bool } std::cout << "######################### Load plugin file: " << pluginFile << std::endl; - if (Ogre::Root::getSingletonPtr() == NULL) { + if (Ogre::Root::getSingletonPtr() == nullptr) { mRoot = new Ogre::Root(pluginFile, "ogre.cfg", "Ogre.log"); } else { mRoot = Ogre::Root::getSingletonPtr(); diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 595ade35ca..98192e58d3 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -142,7 +142,7 @@ template class vpArray2D Basic constructor of a 2D array. Number of columns and rows are set to zero. */ - vpArray2D() : rowNum(0), colNum(0), rowPtrs(NULL), dsize(0), data(NULL) { } + vpArray2D() : rowNum(0), colNum(0), rowPtrs(nullptr), dsize(0), data(nullptr) { } /*! Copy constructor of a 2D array. @@ -190,9 +190,9 @@ template class vpArray2D A.rowNum = 0; A.colNum = 0; - A.rowPtrs = NULL; + A.rowPtrs = nullptr; A.dsize = 0; - A.data = NULL; + A.data = nullptr; } explicit vpArray2D(const std::initializer_list &list) : vpArray2D() @@ -202,7 +202,7 @@ template class vpArray2D } explicit vpArray2D(unsigned int nrows, unsigned int ncols, const std::initializer_list &list) - : rowNum(0), colNum(0), rowPtrs(NULL), dsize(0), data(NULL) + : rowNum(0), colNum(0), rowPtrs(nullptr), dsize(0), data(nullptr) { if (nrows * ncols != static_cast(list.size())) { std::ostringstream oss; @@ -235,14 +235,14 @@ template class vpArray2D */ virtual ~vpArray2D() { - if (data != NULL) { + if (data != nullptr) { free(data); - data = NULL; + data = nullptr; } - if (rowPtrs != NULL) { + if (rowPtrs != nullptr) { free(rowPtrs); - rowPtrs = NULL; + rowPtrs = nullptr; } rowNum = colNum = dsize = 0; } @@ -282,19 +282,19 @@ template class vpArray2D void resize(unsigned int nrows, unsigned int ncols, bool flagNullify = true, bool recopy_ = true) { if ((nrows == rowNum) && (ncols == colNum)) { - if (flagNullify && this->data != NULL) { + if (flagNullify && this->data != nullptr) { memset(this->data, 0, this->dsize * sizeof(Type)); } } else { bool recopy = !flagNullify && recopy_; // priority to flagNullify const bool recopyNeeded = (ncols != this->colNum && this->colNum > 0 && ncols > 0 && (!flagNullify || recopy)); - Type *copyTmp = NULL; + Type *copyTmp = nullptr; unsigned int rowTmp = 0, colTmp = 0; // Recopy case per case is required if number of cols has changed; // structure of Type array is not the same in this case. - if (recopyNeeded && this->data != NULL) { + if (recopyNeeded && this->data != nullptr) { copyTmp = new Type[this->dsize]; memcpy(copyTmp, this->data, sizeof(Type) * this->dsize); rowTmp = this->rowNum; @@ -304,16 +304,16 @@ template class vpArray2D // Reallocation of this->data array this->dsize = nrows * ncols; this->data = (Type *)realloc(this->data, this->dsize * sizeof(Type)); - if ((NULL == this->data) && (0 != this->dsize)) { - if (copyTmp != NULL) { + if ((nullptr == this->data) && (0 != this->dsize)) { + if (copyTmp != nullptr) { delete[] copyTmp; } throw(vpException(vpException::memoryAllocationError, "Memory allocation error when allocating 2D array data")); } this->rowPtrs = (Type **)realloc(this->rowPtrs, nrows * sizeof(Type *)); - if ((NULL == this->rowPtrs) && (0 != this->dsize)) { - if (copyTmp != NULL) { + if ((nullptr == this->rowPtrs) && (0 != this->dsize)) { + if (copyTmp != nullptr) { delete[] copyTmp; } throw(vpException(vpException::memoryAllocationError, @@ -335,7 +335,7 @@ template class vpArray2D if (flagNullify) { memset(this->data, 0, (size_t)(this->dsize) * sizeof(Type)); } - else if (recopyNeeded && this->rowPtrs != NULL) { + else if (recopyNeeded && this->rowPtrs != nullptr) { // Recopy... unsigned int minRow = (this->rowNum < rowTmp) ? this->rowNum : rowTmp; unsigned int minCol = (this->colNum < colTmp) ? this->colNum : colTmp; @@ -351,7 +351,7 @@ template class vpArray2D } } - if (copyTmp != NULL) { + if (copyTmp != nullptr) { delete[] copyTmp; } } @@ -394,10 +394,10 @@ template class vpArray2D void insert(const vpArray2D &A, unsigned int r, unsigned int c) { if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { - if (A.colNum == colNum && data != NULL && A.data != NULL && A.data != data) { + if (A.colNum == colNum && data != nullptr && A.data != nullptr && A.data != data) { memcpy(data + r * colNum, A.data, sizeof(Type) * A.size()); } - else if (data != NULL && A.data != NULL && A.data != data) { + else if (data != nullptr && A.data != nullptr && A.data != data) { for (unsigned int i = r; i < (r + A.getRows()); i++) { memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(Type) * A.colNum); } @@ -431,7 +431,7 @@ template class vpArray2D vpArray2D &operator=(const vpArray2D &A) { resize(A.rowNum, A.colNum, false, false); - if (data != NULL && A.data != NULL && data != A.data) { + if (data != nullptr && A.data != nullptr && data != A.data) { memcpy(data, A.data, (size_t)rowNum * (size_t)colNum * sizeof(Type)); } return *this; @@ -451,9 +451,9 @@ template class vpArray2D other.rowNum = 0; other.colNum = 0; - other.rowPtrs = NULL; + other.rowPtrs = nullptr; other.dsize = 0; - other.data = NULL; + other.data = nullptr; } return *this; @@ -503,7 +503,7 @@ template class vpArray2D */ friend std::ostream &operator<<(std::ostream &s, const vpArray2D &A) { - if (A.data == NULL || A.size() == 0) { + if (A.data == nullptr || A.size() == 0) { return s; } std::ios_base::fmtflags original_flags = s.flags(); @@ -554,7 +554,7 @@ template class vpArray2D \sa save() */ - static bool load(const std::string &filename, vpArray2D &A, bool binary = false, char *header = NULL) + static bool load(const std::string &filename, vpArray2D &A, bool binary = false, char *header = nullptr) { std::fstream file; @@ -595,7 +595,7 @@ template class vpArray2D } } while (!headerIsDecoded); - if (header != NULL) { + if (header != nullptr) { #if defined(__MINGW32__) || \ !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX snprintf(header, h.size() + 1, "%s", h.c_str()); @@ -630,7 +630,7 @@ template class vpArray2D file.read(&c, 1); h += c; } - if (header != NULL) { + if (header != nullptr) { #if defined(__MINGW32__) || \ !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX snprintf(header, h.size() + 1, "%s", h.c_str()); @@ -668,7 +668,7 @@ template class vpArray2D \sa saveYAML() */ - static bool loadYAML(const std::string &filename, vpArray2D &A, char *header = NULL) + static bool loadYAML(const std::string &filename, vpArray2D &A, char *header = nullptr) { std::fstream file; @@ -726,7 +726,7 @@ template class vpArray2D } } - if (header != NULL) { + if (header != nullptr) { std::string h_ = h.substr(0, h.size() - 1); // Remove last '\n' char #if defined(__MINGW32__) || \ !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX diff --git a/modules/core/include/visp3/core/vpColVector.h b/modules/core/include/visp3/core/vpColVector.h index 6f0bc5ef96..56111c54f3 100644 --- a/modules/core/include/visp3/core/vpColVector.h +++ b/modules/core/include/visp3/core/vpColVector.h @@ -256,14 +256,14 @@ class VISP_EXPORT vpColVector : public vpArray2D */ void clear() { - if (data != NULL) { + if (data != nullptr) { free(data); - data = NULL; + data = nullptr; } - if (rowPtrs != NULL) { + if (rowPtrs != nullptr) { free(rowPtrs); - rowPtrs = NULL; + rowPtrs = nullptr; } rowNum = colNum = dsize = 0; } diff --git a/modules/core/include/visp3/core/vpDebug.h b/modules/core/include/visp3/core/vpDebug.h index abce2f9162..04c99805a7 100644 --- a/modules/core/include/visp3/core/vpDebug.h +++ b/modules/core/include/visp3/core/vpDebug.h @@ -152,7 +152,7 @@ class vpTraceOutput \note Call the constructor with something like vpTraceOutput(__FILE__,__LINE__, __FUNCTION__). */ - vpTraceOutput(const char *file, int line, const char *func, bool error = false, const char *s = NULL) + vpTraceOutput(const char *file, int line, const char *func, bool error = false, const char *s = nullptr) : currentFile(file), currentFunc(func), currentLine(line), err(error), header(s) { } @@ -216,7 +216,7 @@ class vpTraceOutput // if we want to write to std::cerr/stderr if (err) { // first writes the header if there is one - if (header != NULL) + if (header != nullptr) std::cerr << header; // then writes the recorded namefile, function and line std::cerr << "!!\t" << currentFile << ": " << currentFunc << "(#" << currentLine << ") : "; @@ -227,7 +227,7 @@ class vpTraceOutput fflush(stderr); } else { // first writes the header if there is one - if (header != NULL) + if (header != nullptr) std::cout << header; // then writes the recorded namefile, function and line std::cout << currentFile << ": " << currentFunc << "(#" << currentLine << ") : "; diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 6dffe6105e..917471c571 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -119,7 +119,7 @@ class VISP_EXPORT vpException : public std::exception /*! * Send a pointer on the array of \e char related to the error string. - * Cannot be \e NULL. + * Cannot be \e nullptr. */ const char *getMessage() const; diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 76dc22b44c..ff73fe7eca 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -190,7 +190,7 @@ template class vpImage // Look for the minumum and the maximum value within the bitmap void getMinMaxValue(Type &min, Type &max, bool onlyFiniteVal = true) const; // Look for the minumum and the maximum value within the bitmap and get their location - void getMinMaxLoc(vpImagePoint *minLoc, vpImagePoint *maxLoc, Type *minVal = NULL, Type *maxVal = NULL) const; + void getMinMaxLoc(vpImagePoint *minLoc, vpImagePoint *maxLoc, Type *minVal = nullptr, Type *maxVal = nullptr) const; /*! Get the image number of pixels which corresponds to the image @@ -352,7 +352,7 @@ template class vpImage template std::ostream &operator<<(std::ostream &s, const vpImage &I) { - if (I.bitmap == NULL) { + if (I.bitmap == nullptr) { return s; } @@ -375,7 +375,7 @@ template std::ostream &operator<<(std::ostream &s, const vpImage &I) { - if (I.bitmap == NULL) { + if (I.bitmap == nullptr) { return s; } @@ -401,7 +401,7 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { - if (I.bitmap == NULL) { + if (I.bitmap == nullptr) { return s; } @@ -427,7 +427,7 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { - if (I.bitmap == NULL) { + if (I.bitmap == nullptr) { return s; } @@ -454,7 +454,7 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { - if (I.bitmap == NULL) { + if (I.bitmap == nullptr) { return s; } @@ -490,7 +490,7 @@ struct vpImageLut_Param_t unsigned char m_lut[256]; unsigned char *m_bitmap; - vpImageLut_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(NULL) { } + vpImageLut_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(nullptr) { } vpImageLut_Param_t(unsigned int start_index, unsigned int end_index, unsigned char *bitmap) : m_start_index(start_index), m_end_index(end_index), m_lut(), m_bitmap(bitmap) @@ -558,7 +558,7 @@ struct vpImageLutRGBa_Param_t vpRGBa m_lut[256]; unsigned char *m_bitmap; - vpImageLutRGBa_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(NULL) { } + vpImageLutRGBa_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(nullptr) { } vpImageLutRGBa_Param_t(unsigned int start_index, unsigned int end_index, unsigned char *bitmap) : m_start_index(start_index), m_end_index(end_index), m_lut(), m_bitmap(bitmap) @@ -637,20 +637,20 @@ template void vpImage::init(unsigned int h, unsigned int w, T template void vpImage::init(unsigned int h, unsigned int w) { if (h != this->height) { - if (row != NULL) { + if (row != nullptr) { vpDEBUG_TRACE(10, "Destruction row[]"); delete[] row; - row = NULL; + row = nullptr; } } if ((h != this->height) || (w != this->width)) { - if (bitmap != NULL) { + if (bitmap != nullptr) { vpDEBUG_TRACE(10, "Destruction bitmap[]"); if (hasOwnership) { delete[] bitmap; } - bitmap = NULL; + bitmap = nullptr; } } @@ -659,18 +659,18 @@ template void vpImage::init(unsigned int h, unsigned int w) npixels = width * height; - if (bitmap == NULL) { + if (bitmap == nullptr) { bitmap = new Type[npixels]; hasOwnership = true; } - if (bitmap == NULL) { + if (bitmap == nullptr) { throw(vpException(vpException::memoryAllocationError, "cannot allocate bitmap ")); } - if (row == NULL) + if (row == nullptr) row = new Type *[height]; - if (row == NULL) { + if (row == nullptr) { throw(vpException(vpException::memoryAllocationError, "cannot allocate row ")); } @@ -684,19 +684,19 @@ template void vpImage::init(unsigned int h, unsigned int w) template void vpImage::init(Type *const array, unsigned int h, unsigned int w, bool copyData) { if (h != this->height) { - if (row != NULL) { + if (row != nullptr) { delete[] row; - row = NULL; + row = nullptr; } } // Delete bitmap if copyData==false, otherwise only if the dimension differs if ((copyData && ((h != this->height) || (w != this->width))) || !copyData) { - if (bitmap != NULL) { + if (bitmap != nullptr) { if (hasOwnership) { delete[] bitmap; } - bitmap = NULL; + bitmap = nullptr; } } @@ -707,10 +707,10 @@ template void vpImage::init(Type *const array, unsigned int h npixels = width * height; if (copyData) { - if (bitmap == NULL) + if (bitmap == nullptr) bitmap = new Type[npixels]; - if (bitmap == NULL) { + if (bitmap == nullptr) { throw(vpException(vpException::memoryAllocationError, "cannot allocate bitmap ")); } @@ -722,9 +722,9 @@ template void vpImage::init(Type *const array, unsigned int h bitmap = array; } - if (row == NULL) + if (row == nullptr) row = new Type *[height]; - if (row == NULL) { + if (row == nullptr) { throw(vpException(vpException::memoryAllocationError, "cannot allocate row ")); } @@ -738,7 +738,7 @@ template void vpImage::init(Type *const array, unsigned int h */ template vpImage::vpImage(unsigned int h, unsigned int w) - : bitmap(NULL), display(NULL), npixels(0), width(0), height(0), row(NULL), hasOwnership(true) + : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { init(h, w, 0); } @@ -748,7 +748,7 @@ vpImage::vpImage(unsigned int h, unsigned int w) */ template vpImage::vpImage(unsigned int h, unsigned int w, Type value) - : bitmap(NULL), display(NULL), npixels(0), width(0), height(0), row(NULL), hasOwnership(true) + : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { init(h, w, value); } @@ -758,7 +758,7 @@ vpImage::vpImage(unsigned int h, unsigned int w, Type value) */ template vpImage::vpImage(Type *const array, unsigned int h, unsigned int w, bool copyData) - : bitmap(NULL), display(NULL), npixels(0), width(0), height(0), row(NULL), hasOwnership(true) + : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { init(array, h, w, copyData); } @@ -767,7 +767,7 @@ vpImage::vpImage(Type *const array, unsigned int h, unsigned int w, bool c \relates vpImage */ template -vpImage::vpImage() : bitmap(NULL), display(NULL), npixels(0), width(0), height(0), row(NULL), hasOwnership(true) +vpImage::vpImage() : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { } /*! @@ -823,20 +823,20 @@ template void vpImage::destroy() { // vpERROR_TRACE("Deallocate "); - if (bitmap != NULL) { + if (bitmap != nullptr) { // vpERROR_TRACE("Deallocate bitmap memory %p",bitmap); // vpDEBUG_TRACE(20,"Deallocate bitmap memory %p",bitmap); if (hasOwnership) { delete[] bitmap; } - bitmap = NULL; + bitmap = nullptr; } - if (row != NULL) { + if (row != nullptr) { // vpERROR_TRACE("Deallocate row memory %p",row); // vpDEBUG_TRACE(20,"Deallocate row memory %p",row); delete[] row; - row = NULL; + row = nullptr; } } @@ -853,7 +853,7 @@ template vpImage::~vpImage() { destroy(); } */ template vpImage::vpImage(const vpImage &I) - : bitmap(NULL), display(NULL), npixels(0), width(0), height(0), row(NULL), hasOwnership(true) + : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { resize(I.getHeight(), I.getWidth()); memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); @@ -867,12 +867,12 @@ vpImage::vpImage(vpImage &&I) : bitmap(I.bitmap), display(I.display), npixels(I.npixels), width(I.width), height(I.height), row(I.row), hasOwnership(I.hasOwnership) { - I.bitmap = NULL; - I.display = NULL; + I.bitmap = nullptr; + I.display = nullptr; I.npixels = 0; I.width = 0; I.height = 0; - I.row = NULL; + I.row = nullptr; I.hasOwnership = false; } @@ -1203,13 +1203,13 @@ template <> inline void vpImage::getMinMaxValue(vpRGBf &min, vpRGBf &max //[...] Fill I vpImagePoint min_loc; double min_val = 0.0; - I.getMinMaxLoc(&min_loc, NULL, &min_val, NULL); + I.getMinMaxLoc(&min_loc, nullptr, &min_val, nullptr); \endcode - \param minLoc : Position of the pixel with minimum value if not NULL. - \param maxLoc : Position of the pixel with maximum value if not NULL. - \param minVal : Minimum pixel value if not NULL. - \param maxVal : Maximum pixel value if not NULL. + \param minLoc : Position of the pixel with minimum value if not nullptr. + \param maxLoc : Position of the pixel with maximum value if not nullptr. + \param minVal : Minimum pixel value if not nullptr. + \param maxVal : Maximum pixel value if not nullptr. \sa getMaxValue() \sa getMinValue() @@ -1238,16 +1238,16 @@ void vpImage::getMinMaxLoc(vpImagePoint *minLoc, vpImagePoint *maxLoc, Typ } } - if (minLoc != NULL) + if (minLoc != nullptr) *minLoc = minLoc_; - if (maxLoc != NULL) + if (maxLoc != nullptr) *maxLoc = maxLoc_; - if (minVal != NULL) + if (minVal != nullptr) *minVal = min; - if (maxVal != NULL) + if (maxVal != nullptr) *maxVal = max; } @@ -1261,7 +1261,7 @@ template vpImage &vpImage::operator=(vpImage othe // vpImage I2(480, 640); // vpDisplayX d(I2); // I2 = I1; //copy only the data - if (other.display != NULL) + if (other.display != nullptr) display = other.display; return *this; diff --git a/modules/core/include/visp3/core/vpImageConvert.h b/modules/core/include/visp3/core/vpImageConvert.h index cb045254b3..1e566d531a 100644 --- a/modules/core/include/visp3/core/vpImageConvert.h +++ b/modules/core/include/visp3/core/vpImageConvert.h @@ -135,7 +135,7 @@ class VISP_EXPORT vpImageConvert #endif static void split(const vpImage &src, vpImage *pR, vpImage *pG, - vpImage *pB, vpImage *pa = NULL); + vpImage *pB, vpImage *pa = nullptr); static void merge(const vpImage *R, const vpImage *G, const vpImage *B, const vpImage *a, vpImage &RGBa); diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index a9a12d081a..068795c12b 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -525,7 +525,7 @@ template class vpUndistortInternalType unsigned int threadid; public: - vpUndistortInternalType() : src(NULL), dst(NULL), width(0), height(0), cam(), nthreads(0), threadid(0) {} + vpUndistortInternalType() : src(nullptr), dst(nullptr), width(0), height(0), cam(), nthreads(0), threadid(0) {} vpUndistortInternalType(const vpUndistortInternalType &u) { *this = u; } vpUndistortInternalType &operator=(const vpUndistortInternalType &u) @@ -609,7 +609,7 @@ template void *vpUndistortInternalType::vpUndistort_threaded( } pthread_exit((void *)0); - return NULL; + return nullptr; } #endif // DOXYGEN_SHOULD_SKIP_THIS #endif // VISP_HAVE_PTHREAD @@ -685,7 +685,7 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c for (unsigned int i = 0; i < nthreads; i++) { // vpTRACE("join thread %d", i); - pthread_join(callThd[i], NULL); + pthread_join(callThd[i], nullptr); } delete[] callThd; diff --git a/modules/core/include/visp3/core/vpList.h b/modules/core/include/visp3/core/vpList.h index f1cd034b63..15edf87bd0 100644 --- a/modules/core/include/visp3/core/vpList.h +++ b/modules/core/include/visp3/core/vpList.h @@ -55,7 +55,7 @@ template class vpListElement { // private: // vpListElement(const vpListElement &) - // : prev(NULL), next(NULL), val() + // : prev(nullptr), next(nullptr), val() // { // throw vpException(vpException::functionNotImplementedError,"Not // implemented!"); @@ -66,7 +66,7 @@ template class vpListElement // } public: - vpListElement() : prev(NULL), next(NULL), val(){}; + vpListElement() : prev(nullptr), next(nullptr), val(){}; vpListElement *prev; ///! pointer to the previous element in the list vpListElement *next; ///! pointer to the next element in the list type val; ///! value of the element @@ -194,10 +194,10 @@ template void vpList::init() first = x; last = y; - x->prev = NULL; + x->prev = nullptr; x->next = y; y->prev = x; - y->next = NULL; + y->next = nullptr; cur = x; nb = 0; @@ -210,7 +210,7 @@ template void vpList::init() \endverbatim \sa init() */ -template vpList::vpList() : nb(0), first(NULL), last(NULL), cur(NULL) { init(); } +template vpList::vpList() : nb(0), first(nullptr), last(nullptr), cur(nullptr) { init(); } /*! \brief vpList destructor @@ -220,8 +220,8 @@ template vpList::~vpList() { kill(); - /*if (first != NULL) */ delete first; - /*if (last != NULL) */ delete last; + /*if (first != nullptr) */ delete first; + /*if (last != nullptr) */ delete last; } /*! @@ -601,7 +601,7 @@ template void vpList::suppress(void) x = cur; cur = cur->next; - if (x != NULL) + if (x != nullptr) delete x; nb--; @@ -673,7 +673,7 @@ template void vpList::operator+=(const type &l) \param l : the list to copy */ -template vpList::vpList(const vpList &l) : nb(0), first(NULL), last(NULL), cur(NULL) +template vpList::vpList(const vpList &l) : nb(0), first(nullptr), last(nullptr), cur(nullptr) { init(); *this = l; diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index 4048374153..3fac0d971c 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -206,14 +206,14 @@ vpMatrix M(R); */ void clear() { - if (data != NULL) { + if (data != nullptr) { free(data); - data = NULL; + data = nullptr; } - if (rowPtrs != NULL) { + if (rowPtrs != nullptr) { free(rowPtrs); - rowPtrs = NULL; + rowPtrs = nullptr; } rowNum = colNum = dsize = 0; } @@ -748,7 +748,7 @@ vpMatrix M(R); \sa saveMatrix(), saveMatrixYAML(), loadMatrixYAML() */ static inline bool loadMatrix(const std::string &filename, vpArray2D &M, bool binary = false, - char *header = NULL) + char *header = nullptr) { return vpArray2D::load(filename, M, binary, header); } @@ -822,7 +822,7 @@ vpMatrix M(R); \sa saveMatrixYAML(), saveMatrix(), loadMatrix() */ - static inline bool loadMatrixYAML(const std::string &filename, vpArray2D &M, char *header = NULL) + static inline bool loadMatrixYAML(const std::string &filename, vpArray2D &M, char *header = nullptr) { return vpArray2D::loadYAML(filename, M, header); } diff --git a/modules/core/include/visp3/core/vpMoment.h b/modules/core/include/visp3/core/vpMoment.h index 1074561c3b..bfdb378b35 100644 --- a/modules/core/include/visp3/core/vpMoment.h +++ b/modules/core/include/visp3/core/vpMoment.h @@ -120,7 +120,7 @@ class VISP_EXPORT vpMoment // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpMoment(const vpMoment &) - // : object(NULL), moments(NULL), values() + // : object(nullptr), moments(nullptr), values() // { // throw vpException(vpException::functionNotImplementedError,"Not // implemented!"); diff --git a/modules/core/include/visp3/core/vpMutex.h b/modules/core/include/visp3/core/vpMutex.h index 96a8fc0501..a9aaf12e1e 100644 --- a/modules/core/include/visp3/core/vpMutex.h +++ b/modules/core/include/visp3/core/vpMutex.h @@ -72,16 +72,16 @@ class vpMutex vpMutex() : m_mutex() { #if defined(VISP_HAVE_PTHREAD) - pthread_mutex_init(&m_mutex, NULL); + pthread_mutex_init(&m_mutex, nullptr); #elif defined(_WIN32) #ifdef WINRT_8_1 - m_mutex = CreateMutexEx(NULL, NULL, 0, NULL); + m_mutex = CreateMutexEx(nullptr, nullptr, 0, nullptr); #else - m_mutex = CreateMutex(NULL, // default security attributes + m_mutex = CreateMutex(nullptr, // default security attributes FALSE, // initially not owned - NULL); // unnamed mutex + nullptr); // unnamed mutex #endif - if (m_mutex == NULL) { + if (m_mutex == nullptr) { std::cout << "CreateMutex error: " << GetLastError() << std::endl; return; } diff --git a/modules/core/include/visp3/core/vpNetwork.h b/modules/core/include/visp3/core/vpNetwork.h index 0daa9a5173..45da39ad9f 100644 --- a/modules/core/include/visp3/core/vpNetwork.h +++ b/modules/core/include/visp3/core/vpNetwork.h @@ -304,7 +304,7 @@ template int vpNetwork::receive(T *object, const unsigned int &size socketMax = receptor_list[i].socketFileDescriptorReceptor; } - int value = select((int)socketMax + 1, &readFileDescriptor, NULL, NULL, &tv); + int value = select((int)socketMax + 1, &readFileDescriptor, nullptr, nullptr, &tv); int numbytes = 0; if (value == -1) { @@ -381,7 +381,7 @@ int vpNetwork::receiveFrom(T *object, const unsigned int &receptorEmitting, cons socketMax = receptor_list[receptorEmitting].socketFileDescriptorReceptor; FD_SET((unsigned int)receptor_list[receptorEmitting].socketFileDescriptorReceptor, &readFileDescriptor); - int value = select((int)socketMax + 1, &readFileDescriptor, NULL, NULL, &tv); + int value = select((int)socketMax + 1, &readFileDescriptor, nullptr, nullptr, &tv); int numbytes = 0; if (value == -1) { diff --git a/modules/core/include/visp3/core/vpRansac.h b/modules/core/include/visp3/core/vpRansac.h index fedd345f98..d1b0f83530 100644 --- a/modules/core/include/visp3/core/vpRansac.h +++ b/modules/core/include/visp3/core/vpRansac.h @@ -69,7 +69,7 @@ template class vpRansac public: static bool ransac(unsigned int npts, const vpColVector &x, unsigned int s, double t, vpColVector &model, vpColVector &inliers, int consensus = 1000, double not_used = 0.0, int maxNbumbersOfTrials = 10000, - double *residual = NULL); + double *residual = nullptr); }; /*! @@ -131,7 +131,7 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, int bestscore = -1; double N = 1; // Dummy initialisation for number of trials. - vpUniRand random((const long)time(NULL)); + vpUniRand random((const long)time(nullptr)); vpColVector bestinliers; unsigned int *ind = new unsigned int[s]; int ninliers = 0; @@ -171,7 +171,7 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, vpTransformation::computeResidual(x, M, d); // Find the indices of points that are inliers to this model. - if (residual != NULL) + if (residual != nullptr) *residual = 0.0; ninliers = 0; for (unsigned int i = 0; i < npts; i++) { @@ -179,7 +179,7 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, if (resid < t) { inliers[i] = 1; ninliers++; - if (residual != NULL) { + if (residual != nullptr) { *residual += fabs(d[i]); } } else @@ -222,7 +222,7 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, M = 0; } - if (residual != NULL) { + if (residual != nullptr) { if (ninliers > 0) { *residual /= ninliers; } diff --git a/modules/core/include/visp3/core/vpRowVector.h b/modules/core/include/visp3/core/vpRowVector.h index aeffe809be..830dcb5c51 100644 --- a/modules/core/include/visp3/core/vpRowVector.h +++ b/modules/core/include/visp3/core/vpRowVector.h @@ -130,14 +130,14 @@ class VISP_EXPORT vpRowVector : public vpArray2D */ void clear() { - if (data != NULL) { + if (data != nullptr) { free(data); - data = NULL; + data = nullptr; } - if (rowPtrs != NULL) { + if (rowPtrs != nullptr) { free(rowPtrs); - rowPtrs = NULL; + rowPtrs = nullptr; } rowNum = colNum = dsize = 0; } diff --git a/modules/core/include/visp3/core/vpThread.h b/modules/core/include/visp3/core/vpThread.h index f795aca60f..8420656b82 100644 --- a/modules/core/include/visp3/core/vpThread.h +++ b/modules/core/include/visp3/core/vpThread.h @@ -92,7 +92,7 @@ class vpThread arguments. \param fn : A pointer to a function. \param args : Arguments passed to the call to \e fn (if any). */ - vpThread(vpThread::Fn fn, vpThread::Args args = NULL) : m_handle(), m_isCreated(false), m_isJoinable(false) + vpThread(vpThread::Fn fn, vpThread::Args args = nullptr) : m_handle(), m_isCreated(false), m_isJoinable(false) { create(fn, args); } @@ -102,18 +102,18 @@ class vpThread execution. \param fn : A pointer to a function. \param args : Arguments passed to the call to \e fn (if any). */ - void create(vpThread::Fn fn, vpThread::Args args = NULL) + void create(vpThread::Fn fn, vpThread::Args args = nullptr) { if (m_isCreated) throw vpException(vpException::fatalError, "The thread is already created"); #if defined(VISP_HAVE_PTHREAD) - int err = pthread_create(&m_handle, NULL, fn, args); + int err = pthread_create(&m_handle, nullptr, fn, args); if (err != 0) { throw vpException(vpException::cannotUseConstructorError, "Can't create thread : %s", strerror(err)); } #elif defined(_WIN32) DWORD dwThreadIdArray; - m_handle = CreateThread(NULL, // default security attributes + m_handle = CreateThread(nullptr, // default security attributes 0, // use default stack size fn, // thread function name args, // argument to thread function @@ -150,7 +150,7 @@ class vpThread { if (m_isJoinable) { #if defined(VISP_HAVE_PTHREAD) - pthread_join(m_handle, NULL); + pthread_join(m_handle, nullptr); #elif defined(_WIN32) #if defined(WINRT_8_1) WaitForSingleObjectEx(m_handle, INFINITE, FALSE); diff --git a/modules/core/include/visp3/core/vpXmlParser.h b/modules/core/include/visp3/core/vpXmlParser.h index e5970f1177..e069a59c9e 100644 --- a/modules/core/include/visp3/core/vpXmlParser.h +++ b/modules/core/include/visp3/core/vpXmlParser.h @@ -127,7 +127,7 @@ void vpDataParser::readMainClass(xmlDocPtr doc, xmlNodePtr node) { - for (xmlNodePtr tmpNode = node->xmlChildrenNode; tmpNode != NULL; tmpNode = tmpNode->next) { + for (xmlNodePtr tmpNode = node->xmlChildrenNode; tmpNode != nullptr; tmpNode = tmpNode->next) { if(tmpNode->type == XML_ELEMENT_NODE) { std::map::iterator iter = this->nodeMap.find((char*)tmpNode->name); diff --git a/modules/core/src/camera/vpMeterPixelConversion.cpp b/modules/core/src/camera/vpMeterPixelConversion.cpp index 5c0f835b42..62282e380a 100644 --- a/modules/core/src/camera/vpMeterPixelConversion.cpp +++ b/modules/core/src/camera/vpMeterPixelConversion.cpp @@ -357,7 +357,7 @@ void vpMeterPixelConversion::convertEllipse(const cv::Mat &cameraMatrix, double \param[in] cameraMatrix : Camera Matrix \f$\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}\f$ \param[in] distCoeffs : Input vector of distortion coefficients \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\f$ of - 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed. + 4, 5, 8, 12 or 14 elements. If the vector is nullptr/empty, the zero distortion coefficients are assumed. \param[in] x : input coordinate in meter along image plane x-axis. \param[in] y : input coordinate in meter along image plane y-axis. \param[out] u : output coordinate in pixels along image horizontal axis. @@ -384,7 +384,7 @@ void vpMeterPixelConversion::convertPoint(const cv::Mat &cameraMatrix, const cv: \param[in] cameraMatrix : Camera Matrix \f$\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}\f$ \param[in] distCoeffs : Input vector of distortion coefficients \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\f$ of - 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed. + 4, 5, 8, 12 or 14 elements. If the vector is nullptr/empty, the zero distortion coefficients are assumed. \param[in] x : input coordinate in meter along image plane x-axis. \param[in] y : input coordinate in meter along image plane y-axis. \param[out] iP : output coordinates in pixels. diff --git a/modules/core/src/camera/vpPixelMeterConversion.cpp b/modules/core/src/camera/vpPixelMeterConversion.cpp index a55ce1c4a0..ba0b8ac767 100644 --- a/modules/core/src/camera/vpPixelMeterConversion.cpp +++ b/modules/core/src/camera/vpPixelMeterConversion.cpp @@ -172,7 +172,7 @@ void vpPixelMeterConversion::convertMoment(const vpCameraParameters &cam, unsign * to meters \f$(x_c, y_c, n_{{20}_m}, n_{{11}_m}, n_{{02}_m})\f$ in the image plane. * \param[in] cameraMatrix : Camera Matrix \f$\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}\f$ * \param[in] distCoeffs : Input vector of distortion coefficients \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, - * k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\f$ of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, + * k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\f$ of 4, 5, 8, 12 or 14 elements. If the vector is nullptr/empty, * the zero distortion coefficients are assumed. * \param[in] center_p : Center of the ellipse (uc, vc) with pixel coordinates. * \param[in] n20_p, n11_p, n02_p : Normalized second order moments of the ellipse in pixels. @@ -281,7 +281,7 @@ void vpPixelMeterConversion::convertMoment(const cv::Mat &cameraMatrix, unsigned \param[in] cameraMatrix : Camera Matrix \f$\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}\f$ \param[in] distCoeffs : Input vector of distortion coefficients \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\f$ of - 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed. + 4, 5, 8, 12 or 14 elements. If the vector is nullptr/empty, the zero distortion coefficients are assumed. \param[in] u : input coordinate in pixels along image horizontal axis. \param[in] v : input coordinate in pixels along image vertical axis. \param[out] x : output coordinate in meter along image plane x-axis. @@ -306,7 +306,7 @@ void vpPixelMeterConversion::convertPoint(const cv::Mat &cameraMatrix, const cv: \param[in] cameraMatrix : Camera Matrix \f$\begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1\end{bmatrix}\f$ \param[in] distCoeffs : Input vector of distortion coefficients \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\f$ of - 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed. + 4, 5, 8, 12 or 14 elements. If the vector is nullptr/empty, the zero distortion coefficients are assumed. \param[in] iP : input coordinates in pixels. \param[out] x : output coordinate in meter along image plane x-axis. \param[out] y : output coordinate in meter along image plane y-axis. diff --git a/modules/core/src/display/vpDisplay.cpp b/modules/core/src/display/vpDisplay.cpp index 4e88163789..51b39c381d 100644 --- a/modules/core/src/display/vpDisplay.cpp +++ b/modules/core/src/display/vpDisplay.cpp @@ -137,7 +137,7 @@ int main() */ void vpDisplay::getImage(const vpImage &Isrc, vpImage &Idest) { - if (Isrc.display != NULL) { + if (Isrc.display != nullptr) { (Isrc.display)->getImage(Idest); } else { @@ -211,7 +211,7 @@ int main() */ void vpDisplay::getImage(const vpImage &Isrc, vpImage &Idest) { - if (Isrc.display != NULL) { + if (Isrc.display != nullptr) { (Isrc.display)->getImage(Idest); } else { diff --git a/modules/core/src/display/vpDisplay_impl.h b/modules/core/src/display/vpDisplay_impl.h index 671fbfba32..33ad7819fa 100644 --- a/modules/core/src/display/vpDisplay_impl.h +++ b/modules/core/src/display/vpDisplay_impl.h @@ -39,15 +39,15 @@ template void vp_display_close(vpImage &I) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->closeDisplay(); - I.display = NULL; + I.display = nullptr; } } template void vp_display_display(const vpImage &I) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayImage(I); } } @@ -56,7 +56,7 @@ template void vp_display_display_arrow(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int w, unsigned int h, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayArrow(ip1, ip2, color, w, h, thickness); } } @@ -65,7 +65,7 @@ template void vp_display_display_arrow(const vpImage &I, int i1, int j1, int i2, int j2, const vpColor &color, unsigned int w, unsigned int h, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip1, ip2; ip1.set_i(i1); ip1.set_j(j1); @@ -106,7 +106,7 @@ template void vp_display_display_char_string(const vpImage &I, const vpImagePoint &ip, const char *string, const vpColor &color) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayCharString(ip, string, color); } } @@ -114,7 +114,7 @@ void vp_display_display_char_string(const vpImage &I, const vpImagePoint & template void vp_display_display_char_string(const vpImage &I, int i, int j, const char *string, const vpColor &color) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip; ip.set_i(i); ip.set_j(j); @@ -127,7 +127,7 @@ template void vp_display_display_circle(const vpImage &I, const vpImagePoint ¢er, unsigned int radius, const vpColor &color, bool fill, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayCircle(center, radius, color, fill, thickness); } } @@ -136,7 +136,7 @@ template void vp_display_display_circle(const vpImage &I, int i, int j, unsigned int radius, const vpColor &color, bool fill, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip; ip.set_i(i); ip.set_j(j); @@ -149,7 +149,7 @@ template void vp_display_display_cross(const vpImage &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayCross(ip, size, color, thickness); } } @@ -158,7 +158,7 @@ template void vp_display_display_cross(const vpImage &I, int i, int j, unsigned int size, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip; ip.set_i(i); ip.set_j(j); @@ -171,7 +171,7 @@ template void vp_display_display_dot_line(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayDotLine(ip1, ip2, color, thickness); } } @@ -180,7 +180,7 @@ template void vp_display_display_dot_line(const vpImage &I, int i1, int j1, int i2, int j2, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip1, ip2; ip1.set_i(i1); ip1.set_j(j1); @@ -196,7 +196,7 @@ void vp_display_display_ellipse(const vpImage &I, const vpImagePoint ¢ const double &highalpha, bool use_normalized_centered_moments, const vpColor &color, unsigned int thickness, bool display_center, bool display_arc) { - if (I.display != NULL) { + if (I.display != nullptr) { double a = 0., b = 0., e = 0.; if (use_normalized_centered_moments) { @@ -399,7 +399,7 @@ template void vp_display_display_line(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayLine(ip1, ip2, color, thickness); } } @@ -408,7 +408,7 @@ template void vp_display_display_line(const vpImage &I, int i1, int j1, int i2, int j2, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip1, ip2; ip1.set_i(i1); ip1.set_j(j1); @@ -422,7 +422,7 @@ template void vp_display_display_point(const vpImage &I, const vpImagePoint &ip, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayPoint(ip, color, thickness); } } @@ -430,7 +430,7 @@ void vp_display_display_point(const vpImage &I, const vpImagePoint &ip, co template void vp_display_display_point(const vpImage &I, int i, int j, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip; ip.set_i(i); ip.set_j(j); @@ -442,7 +442,7 @@ template void vp_display_display_polygon(const vpImage &I, const std::vector &vip, const vpColor &color, unsigned int thickness, bool closed = true) { - if (I.display != NULL) { + if (I.display != nullptr) { if (closed) { for (unsigned int i = 0; i < vip.size(); i++) { (I.display)->displayLine(vip[i], vip[(i + 1) % vip.size()], color, thickness); @@ -460,7 +460,7 @@ template void vp_display_display_rectangle(const vpImage &I, const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, bool fill, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayRectangle(topLeft, width, height, color, fill, thickness); } } @@ -469,7 +469,7 @@ template void vp_display_display_rectangle(const vpImage &I, const vpRect &rectangle, const vpColor &color, bool fill, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayRectangle(rectangle, color, fill, thickness); } } @@ -478,7 +478,7 @@ template void vp_display_display_rectangle(const vpImage &I, const vpImagePoint ¢er, float angle, unsigned int width, unsigned int height, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { double i = center.get_i(); double j = center.get_j(); @@ -506,7 +506,7 @@ template void vp_display_display_rectangle(const vpImage &I, const vpImagePoint &topLeft, const vpImagePoint &bottomRight, const vpColor &color, bool fill, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayRectangle(topLeft, bottomRight, color, fill, thickness); } } @@ -515,7 +515,7 @@ template void vp_display_display_rectangle(const vpImage &I, int i, int j, unsigned int width, unsigned int height, const vpColor &color, bool fill, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint topLeft; topLeft.set_i(i); topLeft.set_j(j); @@ -528,7 +528,7 @@ template void vp_display_display_rectangle(const vpImage &I, unsigned int i, unsigned int j, float angle, unsigned int width, unsigned int height, const vpColor &color, unsigned int thickness) { - if (I.display != NULL) { + if (I.display != nullptr) { // A, B, C, D, corners of the rectangle clockwise vpImagePoint ipa, ipb, ipc, ipd; float cosinus = cos(angle); @@ -562,28 +562,28 @@ template void vp_display_display_roi(const vpImage &I, const throw(vpException(vpException::dimensionError, "Region of interest outside of the image")); } - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayImageROI(I, vpImagePoint(top, left), (unsigned int)roiwidth, (unsigned int)roiheight); } } template void vp_display_flush(const vpImage &I) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->flushDisplay(); } } template void vp_display_flush_roi(const vpImage &I, const vpRect &roi) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->flushDisplayROI(roi.getTopLeft(), (unsigned int)roi.getWidth(), (unsigned int)roi.getHeight()); } } template bool vp_display_get_click(const vpImage &I, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getClick(blocking); } return false; @@ -591,7 +591,7 @@ template bool vp_display_get_click(const vpImage &I, bool blo template bool vp_display_get_click(const vpImage &I, vpImagePoint &ip, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getClick(ip, blocking); } return false; @@ -601,7 +601,7 @@ template bool vp_display_get_click(const vpImage &I, vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getClick(ip, button, blocking); } return false; @@ -611,7 +611,7 @@ template bool vp_display_get_click_up(const vpImage &I, vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getClickUp(ip, button, blocking); } return false; @@ -619,7 +619,7 @@ bool vp_display_get_click_up(const vpImage &I, vpImagePoint &ip, vpMouseBu template bool vp_display_get_keyboard_event(const vpImage &I, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getKeyboardEvent(blocking); } return false; @@ -627,7 +627,7 @@ template bool vp_display_get_keyboard_event(const vpImage &I, template bool vp_display_get_keyboard_event(const vpImage &I, std::string &key, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getKeyboardEvent(key, blocking); } return false; @@ -635,7 +635,7 @@ template bool vp_display_get_keyboard_event(const vpImage &I, template bool vp_display_get_keyboard_event(const vpImage &I, char *key, bool blocking) { - if (I.display != NULL) { + if (I.display != nullptr) { std::string str; bool ret = (I.display)->getKeyboardEvent(str, blocking); snprintf(key, str.size(), "%s", str.c_str()); @@ -646,7 +646,7 @@ template bool vp_display_get_keyboard_event(const vpImage &I, template bool vp_display_get_pointer_motion_event(const vpImage &I, vpImagePoint &ip) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getPointerMotionEvent(ip); } return false; @@ -654,7 +654,7 @@ template bool vp_display_get_pointer_motion_event(const vpImage bool vp_display_get_pointer_position(const vpImage &I, vpImagePoint &ip) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getPointerPosition(ip); } return false; @@ -662,7 +662,7 @@ template bool vp_display_get_pointer_position(const vpImage & template void vp_display_set_background(const vpImage &I, const vpColor &color) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->clearDisplay(color); } } @@ -670,7 +670,7 @@ template void vp_display_set_background(const vpImage &I, con template void vp_display_display_text(const vpImage &I, const vpImagePoint &ip, const std::string &s, const vpColor &color) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->displayCharString(ip, s.c_str(), color); } } @@ -678,7 +678,7 @@ void vp_display_display_text(const vpImage &I, const vpImagePoint &ip, con template void vp_display_display_text(const vpImage &I, int i, int j, const std::string &s, const vpColor &color) { - if (I.display != NULL) { + if (I.display != nullptr) { vpImagePoint ip; ip.set_i(i); ip.set_j(j); @@ -689,28 +689,28 @@ void vp_display_display_text(const vpImage &I, int i, int j, const std::st template void vp_display_set_font(const vpImage &I, const std::string &fontname) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->setFont(fontname); } } template void vp_display_set_title(const vpImage &I, const std::string &windowtitle) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->setTitle(windowtitle); } } template void vp_display_set_window_position(const vpImage &I, int winx, int winy) { - if (I.display != NULL) { + if (I.display != nullptr) { (I.display)->setWindowPosition(winx, winy); } } template unsigned int vp_display_get_down_scaling_factor(const vpImage &I) { - if (I.display != NULL) { + if (I.display != nullptr) { return (I.display)->getDownScalingFactor(); } else { diff --git a/modules/core/src/image/private/stb_truetype.h b/modules/core/src/image/private/stb_truetype.h index 947d323c71..7d9332ddb1 100644 --- a/modules/core/src/image/private/stb_truetype.h +++ b/modules/core/src/image/private/stb_truetype.h @@ -1210,7 +1210,7 @@ static stbtt__buf stbtt__new_buf(const void *p, size_t size) static stbtt__buf stbtt__buf_range(const stbtt__buf *b, int o, int s) { - stbtt__buf r = stbtt__new_buf(NULL, 0); + stbtt__buf r = stbtt__new_buf(nullptr, 0); if (o < 0 || s < 0 || o > b->size || s > b->size - o) return r; r.data = b->data + o; @@ -1401,11 +1401,11 @@ static stbtt__buf stbtt__get_subrs(stbtt__buf cff, stbtt__buf fontdict) stbtt__buf pdict; stbtt__dict_get_ints(&fontdict, 18, 2, private_loc); if (!private_loc[1] || !private_loc[0]) - return stbtt__new_buf(NULL, 0); + return stbtt__new_buf(nullptr, 0); pdict = stbtt__buf_range(&cff, private_loc[1], private_loc[0]); stbtt__dict_get_ints(&pdict, 19, 1, &subrsoff); if (!subrsoff) - return stbtt__new_buf(NULL, 0); + return stbtt__new_buf(nullptr, 0); stbtt__buf_seek(&cff, private_loc[1] + subrsoff); return stbtt__cff_get_index(&cff); } @@ -1433,7 +1433,7 @@ static int stbtt_InitFont_internal(stbtt_fontinfo *info, unsigned char *data, in info->data = data; info->fontstart = fontstart; - info->cff = stbtt__new_buf(NULL, 0); + info->cff = stbtt__new_buf(nullptr, 0); cmap = stbtt__find_table(data, fontstart, "cmap"); // required info->loca = stbtt__find_table(data, fontstart, "loca"); // required @@ -1460,8 +1460,8 @@ static int stbtt_InitFont_internal(stbtt_fontinfo *info, unsigned char *data, in if (!cff) return 0; - info->fontdicts = stbtt__new_buf(NULL, 0); - info->fdselect = stbtt__new_buf(NULL, 0); + info->fontdicts = stbtt__new_buf(nullptr, 0); + info->fdselect = stbtt__new_buf(nullptr, 0); // @TODO this should use size from table (not 512MB) info->cff = stbtt__new_buf(data + cff, 512 * 1024 * 1024); @@ -1708,7 +1708,7 @@ STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index) stbtt_int16 numberOfContours; int g; if (info->cff.size) - return stbtt__GetGlyphInfoT2(info, glyph_index, NULL, NULL, NULL, NULL) == 0; + return stbtt__GetGlyphInfoT2(info, glyph_index, nullptr, nullptr, nullptr, nullptr) == 0; g = stbtt__GetGlyfOffset(info, glyph_index); if (g < 0) return 1; @@ -1741,7 +1741,7 @@ static int stbtt__GetGlyphShapeTT(const stbtt_fontinfo *info, int glyph_index, s int num_vertices = 0; int g = stbtt__GetGlyfOffset(info, glyph_index); - *pvertices = NULL; + *pvertices = nullptr; if (g < 0) return 0; @@ -1987,7 +1987,7 @@ typedef struct { #define STBTT__CSCTX_INIT(bounds) \ { \ - bounds, 0, 0, 0, 0, 0, 0, 0, 0, 0, NULL, 0 \ + bounds, 0, 0, 0, 0, 0, 0, 0, 0, 0, nullptr, 0 \ } static void stbtt__track_vertex(stbtt__csctx *c, stbtt_int32 x, stbtt_int32 y) @@ -2062,7 +2062,7 @@ static stbtt__buf stbtt__get_subr(stbtt__buf idx, int n) bias = 1131; n += bias; if (n < 0 || n >= count) - return stbtt__new_buf(NULL, 0); + return stbtt__new_buf(nullptr, 0); return stbtt__cff_index_get(idx, n); } @@ -2091,7 +2091,7 @@ static stbtt__buf stbtt__cid_get_glyph_subrs(const stbtt_fontinfo *info, int gly } } if (fdselector == -1) - stbtt__new_buf(NULL, 0); + stbtt__new_buf(nullptr, 0); return stbtt__get_subrs(info->cff, stbtt__cff_index_get(info->fontdicts, fdselector)); } @@ -2398,7 +2398,7 @@ static int stbtt__GetGlyphShapeT2(const stbtt_fontinfo *info, int glyph_index, s return output_ctx.num_vertices; } } - *pvertices = NULL; + *pvertices = nullptr; return 0; } @@ -2839,7 +2839,7 @@ STBTT_DEF int stbtt_GetGlyphSVG(const stbtt_fontinfo *info, int gl, const char * return 0; svg_doc = stbtt_FindSVGDoc(info, gl); - if (svg_doc != NULL) { + if (svg_doc != nullptr) { *svg = (char *)data + info->svg + ttULONG(svg_doc + 4); return ttULONG(svg_doc + 8); } else { @@ -2928,8 +2928,8 @@ static void *stbtt__hheap_alloc(stbtt__hheap *hh, size_t size, void *userdata) if (hh->num_remaining_in_head_chunk == 0) { int count = (size < 32 ? 2000 : size < 128 ? 800 : 100); stbtt__hheap_chunk *c = (stbtt__hheap_chunk *)STBTT_malloc(sizeof(stbtt__hheap_chunk) + size * count, userdata); - if (c == NULL) - return NULL; + if (c == nullptr) + return nullptr; c->next = hh->head; hh->head = c; hh->num_remaining_in_head_chunk = count; @@ -2986,7 +2986,7 @@ static stbtt__active_edge *stbtt__new_active(stbtt__hheap *hh, stbtt__edge *e, i { stbtt__active_edge *z = (stbtt__active_edge *)stbtt__hheap_alloc(hh, sizeof(*z), userdata); float dxdy = (e->x1 - e->x0) / (e->y1 - e->y0); - STBTT_assert(z != NULL); + STBTT_assert(z != nullptr); if (!z) return z; @@ -3011,7 +3011,7 @@ static stbtt__active_edge *stbtt__new_active(stbtt__hheap *hh, stbtt__edge *e, i { stbtt__active_edge *z = (stbtt__active_edge *)stbtt__hheap_alloc(hh, sizeof(*z), userdata); float dxdy = (e->x1 - e->x0) / (e->y1 - e->y0); - STBTT_assert(z != NULL); + STBTT_assert(z != nullptr); // STBTT_assert(e->y0 <= start_point); if (!z) return z; @@ -3082,7 +3082,7 @@ static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int off_y, void *userdata) { stbtt__hheap hh = {0, 0, 0}; - stbtt__active_edge *active = NULL; + stbtt__active_edge *active = nullptr; int y, j = 0; int max_weight = (255 / vsubsample); // weight per vertical scanline int s; // vertical subsample index @@ -3142,9 +3142,9 @@ static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, while (e->y0 <= scan_y) { if (e->y1 > scan_y) { stbtt__active_edge *z = stbtt__new_active(&hh, e, off_x, scan_y, userdata); - if (z != NULL) { + if (z != nullptr) { // find insertion point - if (active == NULL) + if (active == nullptr) active = z; else if (z->x < active->x) { // insert at front @@ -3460,7 +3460,7 @@ static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int off_y, void *userdata) { stbtt__hheap hh = {0, 0, 0}; - stbtt__active_edge *active = NULL; + stbtt__active_edge *active = nullptr; int y, j = 0, i; float scanline_data[129], *scanline, *scanline2; @@ -3503,7 +3503,7 @@ static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, while (e->y0 <= scan_y_bottom) { if (e->y0 != e->y1) { stbtt__active_edge *z = stbtt__new_active(&hh, e, off_x, scan_y_top, userdata); - if (z != NULL) { + if (z != nullptr) { if (j == 0 && off_y != 0) { if (z->ey < scan_y_top) { // this can happen due to subpixel positioning and some kind of fp rounding error i think @@ -3821,7 +3821,7 @@ static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, float x = 0, y = 0; if (pass == 1) { points = (stbtt__point *)STBTT_malloc(num_points * sizeof(points[0]), userdata); - if (points == NULL) + if (points == nullptr) goto error; } num_points = 0; @@ -3863,7 +3863,7 @@ static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, STBTT_free(*contour_lengths, userdata); *contour_lengths = 0; *num_contours = 0; - return NULL; + return nullptr; } STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, float flatness_in_pixels, stbtt_vertex *vertices, int num_verts, @@ -3872,7 +3872,7 @@ STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, float flatness_in_pixels, { float scale = scale_x > scale_y ? scale_y : scale_x; int winding_count = 0; - int *winding_lengths = NULL; + int *winding_lengths = nullptr; stbtt__point *windings = stbtt_FlattenCurves(vertices, num_verts, flatness_in_pixels / scale, &winding_lengths, &winding_count, userdata); if (windings) { @@ -3899,7 +3899,7 @@ STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info if (scale_y == 0) { if (scale_x == 0) { STBTT_free(vertices, info->userdata); - return NULL; + return nullptr; } scale_y = scale_x; } @@ -3909,7 +3909,7 @@ STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info // now we get the size gbm.w = (ix1 - ix0); gbm.h = (iy1 - iy0); - gbm.pixels = NULL; // in case we error + gbm.pixels = nullptr; // in case we error if (width) *width = gbm.w; @@ -4019,7 +4019,7 @@ static int stbtt_BakeFontBitmap_internal(unsigned char *data, int offset, // fon float scale; int x, y, bottom_y, i; stbtt_fontinfo f; - f.userdata = NULL; + f.userdata = nullptr; if (!stbtt_InitFont(&f, data, offset)) return -1; STBTT_memset(pixels, 0, pw * ph); // background of 0 around pixels @@ -4159,10 +4159,10 @@ STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, in int num_nodes = pw - padding; stbrp_node *nodes = (stbrp_node *)STBTT_malloc(sizeof(*nodes) * num_nodes, alloc_context); - if (context == NULL || nodes == NULL) { - if (context != NULL) + if (context == nullptr || nodes == nullptr) { + if (context != nullptr) STBTT_free(context, alloc_context); - if (nodes != NULL) + if (nodes != nullptr) STBTT_free(nodes, alloc_context); return 0; } @@ -4358,7 +4358,7 @@ STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, const stb ranges[i].v_oversample = (unsigned char)spc->v_oversample; for (j = 0; j < ranges[i].num_chars; ++j) { int x0, y0, x1, y1; - int codepoint = ranges[i].array_of_unicode_codepoints == NULL ? ranges[i].first_unicode_codepoint_in_range + j + int codepoint = ranges[i].array_of_unicode_codepoints == nullptr ? ranges[i].first_unicode_codepoint_in_range + j : ranges[i].array_of_unicode_codepoints[j]; int glyph = stbtt_FindGlyphIndex(info, codepoint); if (glyph == 0 && (spc->skip_missing || missing_glyph_added)) { @@ -4422,7 +4422,7 @@ STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, const if (r->was_packed && r->w != 0 && r->h != 0) { stbtt_packedchar *bc = &ranges[i].chardata_for_range[j]; int advance, lsb, x0, y0, x1, y1; - int codepoint = ranges[i].array_of_unicode_codepoints == NULL ? ranges[i].first_unicode_codepoint_in_range + j + int codepoint = ranges[i].array_of_unicode_codepoints == nullptr ? ranges[i].first_unicode_codepoint_in_range + j : ranges[i].array_of_unicode_codepoints[j]; int glyph = stbtt_FindGlyphIndex(info, codepoint); stbrp_coord pad = (stbrp_coord)spc->padding; @@ -4501,7 +4501,7 @@ STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, const unsigned char n += ranges[i].num_chars; rects = (stbrp_rect *)STBTT_malloc(sizeof(*rects) * n, spc->user_allocator_context); - if (rects == NULL) + if (rects == nullptr) return 0; info.userdata = spc->user_allocator_context; @@ -4523,7 +4523,7 @@ STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, const unsigned char * { stbtt_pack_range range; range.first_unicode_codepoint_in_range = first_unicode_codepoint_in_range; - range.array_of_unicode_codepoints = NULL; + range.array_of_unicode_codepoints = nullptr; range.num_chars = num_chars_in_range; range.chardata_for_range = chardata_for_range; range.font_size = font_size; @@ -4766,13 +4766,13 @@ STBTT_DEF unsigned char *stbtt_GetGlyphSDF(const stbtt_fontinfo *info, float sca unsigned char *data; if (scale == 0) - return NULL; + return nullptr; stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale, scale, 0.0f, 0.0f, &ix0, &iy0, &ix1, &iy1); - // if empty, return NULL + // if empty, return nullptr if (ix0 == ix1 || iy0 == iy1) - return NULL; + return nullptr; ix0 -= padding; iy0 -= padding; @@ -5035,7 +5035,7 @@ STBTT_DEF const char *stbtt_GetFontNameString(const stbtt_fontinfo *font, int *l stbtt_uint32 offset = font->fontstart; stbtt_uint32 nm = stbtt__find_table(fc, offset, "name"); if (!nm) - return NULL; + return nullptr; count = ttUSHORT(fc + nm + 2); stringOffset = nm + ttUSHORT(fc + nm + 4); @@ -5047,7 +5047,7 @@ STBTT_DEF const char *stbtt_GetFontNameString(const stbtt_fontinfo *font, int *l return (const char *)(fc + stringOffset + ttUSHORT(fc + loc + 10)); } } - return NULL; + return nullptr; } static int stbtt__matchpair(stbtt_uint8 *fc, stbtt_uint32 nm, stbtt_uint8 *name, stbtt_int32 nlen, diff --git a/modules/core/src/image/vpGaussianFilter.cpp b/modules/core/src/image/vpGaussianFilter.cpp index 4e116085ab..4a37ca4183 100644 --- a/modules/core/src/image/vpGaussianFilter.cpp +++ b/modules/core/src/image/vpGaussianFilter.cpp @@ -40,7 +40,7 @@ class vpGaussianFilter::Impl { public: Impl(unsigned int width, unsigned int height, float sigma, bool deinterleave) - : m_funcPtrGray(NULL), m_funcPtrRGBa(NULL), m_deinterleave(deinterleave) + : m_funcPtrGray(nullptr), m_funcPtrRGBa(nullptr), m_deinterleave(deinterleave) { const float epsilon = 0.001f; { @@ -95,7 +95,7 @@ class vpGaussianFilter::Impl SimdGaussianBlurRun(m_funcPtrGray, m_blue.bitmap, m_blue.getWidth(), m_blueBlurred.bitmap, m_blueBlurred.getWidth()); - vpImageConvert::merge(&m_redBlurred, &m_greenBlurred, &m_blueBlurred, NULL, I_blur); + vpImageConvert::merge(&m_redBlurred, &m_greenBlurred, &m_blueBlurred, nullptr, I_blur); } } diff --git a/modules/core/src/image/vpImageConvert.cpp b/modules/core/src/image/vpImageConvert.cpp index 3fe7de60e8..cc4d74ed45 100644 --- a/modules/core/src/image/vpImageConvert.cpp +++ b/modules/core/src/image/vpImageConvert.cpp @@ -3918,10 +3918,10 @@ void vpImageConvert::YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgba, unsi /*! Split an image from vpRGBa format to monochrome channels. \param[in] src : source image. - \param[out] pR : red channel. Set as NULL if not needed. - \param[out] pG : green channel. Set as NULL if not needed. - \param[out] pB : blue channel. Set as NULL if not needed. - \param[out] pa : alpha channel. Set as NULL if not needed. + \param[out] pR : red channel. Set as nullptr if not needed. + \param[out] pG : green channel. Set as nullptr if not needed. + \param[out] pB : blue channel. Set as nullptr if not needed. + \param[out] pa : alpha channel. Set as nullptr if not needed. Output channels are resized if needed. @@ -3946,7 +3946,7 @@ int main() // Split Ic color image // R and B will be resized in split function if needed - vpImageConvert::split(Ic, &R, NULL, &B, NULL); + vpImageConvert::split(Ic, &R, nullptr, &B, nullptr); // Save the the R Channel. vpImageIo::write(R, "RChannel.pgm"); @@ -4009,22 +4009,22 @@ void vpImageConvert::merge(const vpImage *R, const vpImage mapOfWidths, mapOfHeights; - if (R != NULL) { + if (R != nullptr) { mapOfWidths[R->getWidth()]++; mapOfHeights[R->getHeight()]++; } - if (G != NULL) { + if (G != nullptr) { mapOfWidths[G->getWidth()]++; mapOfHeights[G->getHeight()]++; } - if (B != NULL) { + if (B != nullptr) { mapOfWidths[B->getWidth()]++; mapOfHeights[B->getHeight()]++; } - if (a != NULL) { + if (a != nullptr) { mapOfWidths[a->getWidth()]++; mapOfHeights[a->getHeight()]++; } @@ -4035,26 +4035,26 @@ void vpImageConvert::merge(const vpImage *R, const vpImagebitmap, width, G->bitmap, width, B->bitmap, width, a->bitmap, width, width, height, reinterpret_cast(RGBa.bitmap), width * sizeof(vpRGBa)); } else { unsigned int size = width * height; for (unsigned int i = 0; i < size; i++) { - if (R != NULL) { + if (R != nullptr) { RGBa.bitmap[i].R = R->bitmap[i]; } - if (G != NULL) { + if (G != nullptr) { RGBa.bitmap[i].G = G->bitmap[i]; } - if (B != NULL) { + if (B != nullptr) { RGBa.bitmap[i].B = B->bitmap[i]; } - if (a != NULL) { + if (a != nullptr) { RGBa.bitmap[i].A = a->bitmap[i]; } } diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index 7a06e90e30..105f1dc77e 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -161,7 +161,7 @@ void vpColVector::init(const vpColVector &v, unsigned int r, unsigned int nrows) v.getRows())); resize(nrows, false); - if (this->rowPtrs == NULL) // Fix coverity scan: explicit null dereferenced + if (this->rowPtrs == nullptr) // Fix coverity scan: explicit null dereferenced return; // Nothing to do for (unsigned int i = r; i < rnrows; i++) (*this)[i - r] = v[i]; @@ -224,9 +224,9 @@ vpColVector::vpColVector(vpColVector &&v) : vpArray2D() v.rowNum = 0; v.colNum = 0; - v.rowPtrs = NULL; + v.rowPtrs = nullptr; v.dsize = 0; - v.data = NULL; + v.data = nullptr; } vpColVector vpColVector::operator-() const @@ -416,9 +416,9 @@ vpColVector &vpColVector::operator=(vpColVector &&other) other.rowNum = 0; other.colNum = 0; - other.rowPtrs = NULL; + other.rowPtrs = nullptr; other.dsize = 0; - other.data = NULL; + other.data = nullptr; } return *this; @@ -478,10 +478,10 @@ vpColVector operator*(const double &x, const vpColVector &v) double vpColVector::dotProd(const vpColVector &a, const vpColVector &b) { - if (a.data == NULL) { + if (a.data == nullptr) { throw(vpException(vpException::fatalError, "Cannot compute the dot product: first vector empty")); } - if (b.data == NULL) { + if (b.data == nullptr) { throw(vpException(vpException::fatalError, "Cannot compute the dot product: second vector empty")); } if (a.size() != b.size()) { @@ -524,7 +524,7 @@ vpColVector &vpColVector::normalize() vpColVector vpColVector::invSort(const vpColVector &v) { - if (v.data == NULL) { + if (v.data == nullptr) { throw(vpException(vpException::fatalError, "Cannot sort content of column vector: vector empty")); } vpColVector tab; @@ -549,7 +549,7 @@ vpColVector vpColVector::invSort(const vpColVector &v) vpColVector vpColVector::sort(const vpColVector &v) { - if (v.data == NULL) { + if (v.data == nullptr) { throw(vpException(vpException::fatalError, "Cannot sort content of column vector: vector empty")); } vpColVector tab; @@ -619,7 +619,7 @@ void vpColVector::stack(const vpColVector &A, const vpColVector &B, vpColVector double vpColVector::mean(const vpColVector &v) { - if (v.data == NULL || v.size() == 0) { + if (v.data == nullptr || v.size() == 0) { throw(vpException(vpException::dimensionError, "Cannot compute column vector mean: vector empty")); } @@ -631,7 +631,7 @@ double vpColVector::mean(const vpColVector &v) double vpColVector::median(const vpColVector &v) { - if (v.data == NULL || v.size() == 0) { + if (v.data == nullptr || v.size() == 0) { throw(vpException(vpException::dimensionError, "Cannot compute column vector median: vector empty")); } @@ -642,7 +642,7 @@ double vpColVector::median(const vpColVector &v) double vpColVector::stdev(const vpColVector &v, bool useBesselCorrection) { - if (v.data == NULL || v.size() == 0) { + if (v.data == nullptr || v.size() == 0) { throw(vpException(vpException::dimensionError, "Cannot compute column vector stdev: vector empty")); } @@ -709,7 +709,7 @@ void vpColVector::insert(unsigned int i, const vpColVector &v) if (i + v.size() > this->size()) throw(vpException(vpException::dimensionError, "Unable to insert a column vector")); - if (data != NULL && v.data != NULL && v.rowNum > 0) { + if (data != nullptr && v.data != nullptr && v.rowNum > 0) { memcpy(data + i, v.data, sizeof(double) * v.rowNum); } } diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index d238d8e998..83a55a3ba9 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -207,9 +207,9 @@ vpMatrix::vpMatrix(vpMatrix &&A) : vpArray2D() A.rowNum = 0; A.colNum = 0; - A.rowPtrs = NULL; + A.rowPtrs = nullptr; A.dsize = 0; - A.data = NULL; + A.data = nullptr; } /*! @@ -344,7 +344,7 @@ void vpMatrix::init(const vpMatrix &M, unsigned int r, unsigned int c, unsigned M.getCols())); resize(nrows, ncols, false, false); - if (this->rowPtrs == NULL) // Fix coverity scan: explicit null dereferenced + if (this->rowPtrs == nullptr) // Fix coverity scan: explicit null dereferenced return; // Noting to do for (unsigned int i = 0; i < nrows; i++) { memcpy((*this)[i], &M[i + r][c], ncols * sizeof(double)); @@ -642,7 +642,7 @@ vpMatrix &vpMatrix::operator=(const vpArray2D &A) { resize(A.getRows(), A.getCols(), false, false); - if (data != NULL && A.data != NULL && data != A.data) { + if (data != nullptr && A.data != nullptr && data != A.data) { memcpy(data, A.data, dsize * sizeof(double)); } @@ -653,7 +653,7 @@ vpMatrix &vpMatrix::operator=(const vpMatrix &A) { resize(A.getRows(), A.getCols(), false, false); - if (data != NULL && A.data != NULL && data != A.data) { + if (data != nullptr && A.data != nullptr && data != A.data) { memcpy(data, A.data, dsize * sizeof(double)); } @@ -674,9 +674,9 @@ vpMatrix &vpMatrix::operator=(vpMatrix &&other) other.rowNum = 0; other.colNum = 0; - other.rowPtrs = NULL; + other.rowPtrs = nullptr; other.dsize = 0; - other.data = NULL; + other.data = nullptr; } return *this; @@ -2365,7 +2365,7 @@ vpMatrix vpMatrix::pseudoInverseLapack(double svThreshold) const U.insert(*this, 0, 0); U.svdLapack(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return Ap; } @@ -2433,7 +2433,7 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, double svThreshold) con U.insert(*this, 0, 0); U.svdLapack(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } @@ -2507,7 +2507,7 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double U.insert(*this, 0, 0); U.svdLapack(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -2643,7 +2643,7 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double U.insert(*this, 0, 0); U.svdLapack(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, &imA, &imAt, &kerAt); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -2712,7 +2712,7 @@ vpMatrix vpMatrix::pseudoInverseLapack(int rank_in) const U.insert(*this, 0, 0); U.svdLapack(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return Ap; } @@ -2787,7 +2787,7 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, int rank_in) const U.insert(*this, 0, 0); U.svdLapack(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return rank_out; } @@ -2869,7 +2869,7 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in) co U.insert(*this, 0, 0); U.svdLapack(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -3081,7 +3081,7 @@ vpMatrix vpMatrix::pseudoInverseEigen3(double svThreshold) const U.insert(*this, 0, 0); U.svdEigen3(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return Ap; } @@ -3149,7 +3149,7 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, double svThreshold) con U.insert(*this, 0, 0); U.svdEigen3(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } @@ -3223,7 +3223,7 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double U.insert(*this, 0, 0); U.svdEigen3(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -3359,7 +3359,7 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double U.insert(*this, 0, 0); U.svdEigen3(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, &imA, &imAt, &kerAt); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -3428,7 +3428,7 @@ vpMatrix vpMatrix::pseudoInverseEigen3(int rank_in) const U.insert(*this, 0, 0); U.svdEigen3(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return Ap; } @@ -3503,7 +3503,7 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, int rank_in) const U.insert(*this, 0, 0); U.svdEigen3(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return rank_out; } @@ -3585,7 +3585,7 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in) co U.insert(*this, 0, 0); U.svdEigen3(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -3797,7 +3797,7 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(double svThreshold) const U.insert(*this, 0, 0); U.svdOpenCV(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return Ap; } @@ -3865,7 +3865,7 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, double svThreshold) con U.insert(*this, 0, 0); U.svdOpenCV(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } @@ -3939,7 +3939,7 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double U.insert(*this, 0, 0); U.svdOpenCV(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -4075,7 +4075,7 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double U.insert(*this, 0, 0); U.svdOpenCV(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, NULL, &imA, &imAt, &kerAt); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -4144,7 +4144,7 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(int rank_in) const U.insert(*this, 0, 0); U.svdOpenCV(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return Ap; } @@ -4219,7 +4219,7 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, int rank_in) const U.insert(*this, 0, 0); U.svdOpenCV(sv, V); - compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return rank_out; } @@ -4301,7 +4301,7 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in) co U.insert(*this, 0, 0); U.svdOpenCV(sv_, V); - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, NULL, NULL, NULL); + compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); // Remove singular values equal to the one that corresponds to the lines of 0 // introduced when m < n @@ -5270,7 +5270,7 @@ vpRowVector vpMatrix::getRow(unsigned int i, unsigned int j_begin, unsigned int throw(vpException(vpException::dimensionError, "Unable to extract a row vector from the matrix")); vpRowVector r(row_size); - if (r.data != NULL && data != NULL) { + if (r.data != nullptr && data != nullptr) { memcpy(r.data, (*this)[i] + j_begin, row_size * sizeof(double)); } @@ -5370,24 +5370,24 @@ void vpMatrix::stack(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) } } - if (A.data != NULL && A.data == C.data) { + if (A.data != nullptr && A.data == C.data) { std::cerr << "A and C must be two different objects!" << std::endl; return; } - if (B.data != NULL && B.data == C.data) { + if (B.data != nullptr && B.data == C.data) { std::cerr << "B and C must be two different objects!" << std::endl; return; } C.resize(nra + nrb, B.getCols(), false, false); - if (C.data != NULL && A.data != NULL && A.size() > 0) { + if (C.data != nullptr && A.data != nullptr && A.size() > 0) { // Copy A in C memcpy(C.data, A.data, sizeof(double) * A.size()); } - if (C.data != NULL && B.data != NULL && B.size() > 0) { + if (C.data != nullptr && B.data != nullptr && B.size() > 0) { // Copy B in C memcpy(C.data + A.size(), B.data, sizeof(double) * B.size()); } @@ -5423,7 +5423,7 @@ vpMatrix vpMatrix::stack(const vpMatrix &A, const vpRowVector &r) */ void vpMatrix::stack(const vpMatrix &A, const vpRowVector &r, vpMatrix &C) { - if (A.data != NULL && A.data == C.data) { + if (A.data != nullptr && A.data == C.data) { std::cerr << "A and C must be two different objects!" << std::endl; return; } @@ -5462,7 +5462,7 @@ vpMatrix vpMatrix::stack(const vpMatrix &A, const vpColVector &c) */ void vpMatrix::stack(const vpMatrix &A, const vpColVector &c, vpMatrix &C) { - if (A.data != NULL && A.data == C.data) { + if (A.data != nullptr && A.data == C.data) { std::cerr << "A and C must be two different objects!" << std::endl; return; } @@ -5920,7 +5920,7 @@ void vpMatrix::stack(const vpRowVector &r) unsigned int oldSize = size(); resize(rowNum + 1, colNum, false, false); - if (data != NULL && r.data != NULL && data != r.data) { + if (data != nullptr && r.data != nullptr && data != r.data) { // Copy r in data memcpy(data + oldSize, r.data, sizeof(double) * r.size()); } @@ -5962,7 +5962,7 @@ void vpMatrix::stack(const vpColVector &c) unsigned int oldColNum = colNum; resize(rowNum, colNum + 1, false, false); - if (data != NULL && tmp.data != NULL && data != tmp.data) { + if (data != nullptr && tmp.data != nullptr && data != tmp.data) { // Copy c in data for (unsigned int i = 0; i < rowNum; i++) { memcpy(data + i * colNum, tmp.data + i * oldColNum, sizeof(double) * oldColNum); @@ -5985,10 +5985,10 @@ void vpMatrix::stack(const vpColVector &c) void vpMatrix::insert(const vpMatrix &A, unsigned int r, unsigned int c) { if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { - if (A.colNum == colNum && data != NULL && A.data != NULL && A.data != data) { + if (A.colNum == colNum && data != nullptr && A.data != nullptr && A.data != data) { memcpy(data + r * colNum, A.data, sizeof(double) * A.size()); } - else if (data != NULL && A.data != NULL && A.data != data) { + else if (data != nullptr && A.data != nullptr && A.data != data) { for (unsigned int i = r; i < (r + A.getRows()); i++) { memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(double) * A.colNum); } diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 2fda61340a..54cfa3af73 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -136,9 +136,9 @@ vpRowVector &vpRowVector::operator=(vpRowVector &&other) other.rowNum = 0; other.colNum = 0; - other.rowPtrs = NULL; + other.rowPtrs = nullptr; other.dsize = 0; - other.data = NULL; + other.data = nullptr; } return *this; @@ -586,9 +586,9 @@ vpRowVector::vpRowVector(vpRowVector &&v) : vpArray2D() v.rowNum = 0; v.colNum = 0; - v.rowPtrs = NULL; + v.rowPtrs = nullptr; v.dsize = 0; - v.data = NULL; + v.data = nullptr; } /*! @@ -885,7 +885,7 @@ void vpRowVector::stack(const vpRowVector &A, const vpRowVector &B, vpRowVector */ double vpRowVector::mean(const vpRowVector &v) { - if (v.data == NULL || v.size() == 0) { + if (v.data == nullptr || v.size() == 0) { throw(vpException(vpException::dimensionError, "Cannot compute mean value of an empty row vector")); } @@ -902,7 +902,7 @@ double vpRowVector::mean(const vpRowVector &v) */ double vpRowVector::median(const vpRowVector &v) { - if (v.data == NULL || v.size() == 0) { + if (v.data == nullptr || v.size() == 0) { throw(vpException(vpException::dimensionError, "Cannot compute mean value of an empty row vector")); } @@ -916,7 +916,7 @@ double vpRowVector::median(const vpRowVector &v) */ double vpRowVector::stdev(const vpRowVector &v, bool useBesselCorrection) { - if (v.data == NULL || v.size() == 0) { + if (v.data == nullptr || v.size() == 0) { throw(vpException(vpException::dimensionError, "Cannot compute mean value of an empty row vector")); } @@ -1150,7 +1150,7 @@ void vpRowVector::init(const vpRowVector &v, unsigned int c, unsigned int ncols) throw(vpException(vpException::dimensionError, "Bad column dimension (%d > %d) used to initialize vpRowVector", cncols, v.getCols())); resize(ncols); - if (this->rowPtrs == NULL) // Fix coverity scan: explicit null dereferenced + if (this->rowPtrs == nullptr) // Fix coverity scan: explicit null dereferenced return; // Noting to do for (unsigned int i = 0; i < ncols; i++) (*this)[i] = v[i + c]; diff --git a/modules/core/src/math/matrix/vpSubColVector.cpp b/modules/core/src/math/matrix/vpSubColVector.cpp index 4d5875081e..32873ff54b 100644 --- a/modules/core/src/math/matrix/vpSubColVector.cpp +++ b/modules/core/src/math/matrix/vpSubColVector.cpp @@ -42,7 +42,7 @@ #include //! Default constructor that creates an empty vector. -vpSubColVector::vpSubColVector() : vpColVector(), m_pRowNum(0), m_parent(NULL) { } +vpSubColVector::vpSubColVector() : vpColVector(), m_pRowNum(0), m_parent(nullptr) { } /*! * Construct a sub-column vector from a parent column vector. @@ -51,7 +51,7 @@ vpSubColVector::vpSubColVector() : vpColVector(), m_pRowNum(0), m_parent(NULL) { * \param nrows : size of the sub-column vector. */ vpSubColVector::vpSubColVector(vpColVector &v, const unsigned int &offset, const unsigned int &nrows) - : vpColVector(), m_pRowNum(0), m_parent(NULL) + : vpColVector(), m_pRowNum(0), m_parent(nullptr) { init(v, offset, nrows); } @@ -96,9 +96,9 @@ void vpSubColVector::init(vpColVector &v, const unsigned int &offset, const unsi } /*! - * Destructor that set the pointer to the parent column vector to NULL. + * Destructor that set the pointer to the parent column vector to nullptr. */ -vpSubColVector::~vpSubColVector() { data = NULL; } +vpSubColVector::~vpSubColVector() { data = nullptr; } /*! * This method can be used to detect if the parent column vector diff --git a/modules/core/src/math/matrix/vpSubMatrix.cpp b/modules/core/src/math/matrix/vpSubMatrix.cpp index d1e8f73e7b..da9e7c7b7c 100644 --- a/modules/core/src/math/matrix/vpSubMatrix.cpp +++ b/modules/core/src/math/matrix/vpSubMatrix.cpp @@ -42,7 +42,7 @@ #include #include -vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(NULL) {} +vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(nullptr) {} /*! \brief Constructor @@ -54,7 +54,7 @@ vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(NULL) {} */ vpSubMatrix::vpSubMatrix(vpMatrix &m, const unsigned int &row_offset, const unsigned int &col_offset, const unsigned int &nrows, const unsigned int &ncols) - : pRowNum(0), pColNum(0), parent(NULL) + : pRowNum(0), pColNum(0), parent(nullptr) { init(m, row_offset, col_offset, nrows, ncols); } @@ -173,4 +173,4 @@ vpSubMatrix &vpSubMatrix::operator=(const double &x) return *this; } -vpSubMatrix::~vpSubMatrix() { data = NULL; } +vpSubMatrix::~vpSubMatrix() { data = nullptr; } diff --git a/modules/core/src/math/matrix/vpSubRowVector.cpp b/modules/core/src/math/matrix/vpSubRowVector.cpp index 6e64b314e0..6f7b10bc8e 100644 --- a/modules/core/src/math/matrix/vpSubRowVector.cpp +++ b/modules/core/src/math/matrix/vpSubRowVector.cpp @@ -37,7 +37,7 @@ #include //! Default constructor that creates an empty vector. -vpSubRowVector::vpSubRowVector() : vpRowVector(), m_pColNum(0), m_parent(NULL) { } +vpSubRowVector::vpSubRowVector() : vpRowVector(), m_pColNum(0), m_parent(nullptr) { } /*! * Construct a sub-row vector from a parent row vector. @@ -46,7 +46,7 @@ vpSubRowVector::vpSubRowVector() : vpRowVector(), m_pColNum(0), m_parent(NULL) { * \param ncols : size of the sub-row vector. */ vpSubRowVector::vpSubRowVector(vpRowVector &v, const unsigned int &offset, const unsigned int &ncols) - : vpRowVector(), m_pColNum(0), m_parent(NULL) + : vpRowVector(), m_pColNum(0), m_parent(nullptr) { init(v, offset, ncols); } @@ -89,9 +89,9 @@ void vpSubRowVector::init(vpRowVector &v, const unsigned int &offset, const unsi } /*! - * Destructor that set the pointer to the parent row vector to NULL. + * Destructor that set the pointer to the parent row vector to nullptr. */ -vpSubRowVector::~vpSubRowVector() { data = NULL; } +vpSubRowVector::~vpSubRowVector() { data = nullptr; } /*! * This method can be used to detect if the parent row vector diff --git a/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp b/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp index 3d8684263d..f4b3f8046e 100644 --- a/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp +++ b/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp @@ -102,7 +102,7 @@ BOOL IsWow64() LPFN_ISWOW64PROCESS fnIsWow64Process = (LPFN_ISWOW64PROCESS)GetProcAddress( GetModuleHandle(TEXT("kernel32")), "IsWow64Process"); - if (NULL != fnIsWow64Process) { + if (nullptr != fnIsWow64Process) { if (!fnIsWow64Process(GetCurrentProcess(), &bIsWow64)) { printf("Error Detecting Operating System.\n"); printf("Defaulting to 32-bit OS.\n\n"); diff --git a/modules/core/src/tools/file/vpIoTools.cpp b/modules/core/src/tools/file/vpIoTools.cpp index a5d90de5f5..7a2c66ea11 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -1723,7 +1723,7 @@ std::string vpIoTools::getAbsolutePathname(const std::string &pathname) #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX std::string real_path_str = pathname; - char *real_path = realpath(pathname.c_str(), NULL); + char *real_path = realpath(pathname.c_str(), nullptr); if (real_path) { real_path_str = real_path; @@ -2030,8 +2030,8 @@ std::vector vpIoTools::getDirFiles(const std::string &pathname) #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX std::vector files; - struct dirent **list = NULL; - int filesCount = scandir(dirName.c_str(), &list, NULL, NULL); + struct dirent **list = nullptr; + int filesCount = scandir(dirName.c_str(), &list, nullptr, nullptr); if (filesCount == -1) { throw(vpIoException(vpException::fatalError, "Cannot read files of directory %s", dirName.c_str())); } diff --git a/modules/core/src/tools/geometry/vpPolygon3D.cpp b/modules/core/src/tools/geometry/vpPolygon3D.cpp index 272e9e65a5..bf8f6b1e8f 100644 --- a/modules/core/src/tools/geometry/vpPolygon3D.cpp +++ b/modules/core/src/tools/geometry/vpPolygon3D.cpp @@ -51,13 +51,13 @@ Basic constructor. */ vpPolygon3D::vpPolygon3D() - : nbpt(0), nbCornersInsidePrev(0), p(NULL), polyClipped(), clippingFlag(vpPolygon3D::NO_CLIPPING), + : nbpt(0), nbCornersInsidePrev(0), p(nullptr), polyClipped(), clippingFlag(vpPolygon3D::NO_CLIPPING), distNearClip(0.001), distFarClip(100.) { } vpPolygon3D::vpPolygon3D(const vpPolygon3D &mbtp) - : nbpt(mbtp.nbpt), nbCornersInsidePrev(mbtp.nbCornersInsidePrev), p(NULL), polyClipped(mbtp.polyClipped), + : nbpt(mbtp.nbpt), nbCornersInsidePrev(mbtp.nbCornersInsidePrev), p(nullptr), polyClipped(mbtp.polyClipped), clippingFlag(mbtp.clippingFlag), distNearClip(mbtp.distNearClip), distFarClip(mbtp.distFarClip) { if (p) @@ -90,9 +90,9 @@ vpPolygon3D &vpPolygon3D::operator=(const vpPolygon3D &mbtp) */ vpPolygon3D::~vpPolygon3D() { - if (p != NULL) { + if (p != nullptr) { delete[] p; - p = NULL; + p = nullptr; } } @@ -119,7 +119,7 @@ vpPoint &vpPolygon3D::getPoint(const unsigned int _index) void vpPolygon3D::setNbPoint(unsigned int nb) { nbpt = nb; - if (p != NULL) + if (p != nullptr) delete[] p; p = new vpPoint[nb]; } @@ -132,7 +132,7 @@ void vpPolygon3D::setNbPoint(unsigned int nb) */ void vpPolygon3D::addPoint(unsigned int n, const vpPoint &P) { - // if( p!NULL && n < nbpt ) + // if( p!nullptr && n < nbpt ) p[n] = P; } diff --git a/modules/core/src/tools/histogram/vpHistogram.cpp b/modules/core/src/tools/histogram/vpHistogram.cpp index de74e105c6..5fa5f6fcb2 100644 --- a/modules/core/src/tools/histogram/vpHistogram.cpp +++ b/modules/core/src/tools/histogram/vpHistogram.cpp @@ -61,15 +61,15 @@ struct vpHistogram_Param_t unsigned int *m_histogram; const vpImage *m_I; - vpHistogram_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_histogram(NULL), m_I(NULL) { } + vpHistogram_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_histogram(nullptr), m_I(nullptr) { } vpHistogram_Param_t(unsigned int start_index, unsigned int end_index, const vpImage *const I) - : m_start_index(start_index), m_end_index(end_index), m_lut(), m_histogram(NULL), m_I(I) + : m_start_index(start_index), m_end_index(end_index), m_lut(), m_histogram(nullptr), m_I(I) { } ~vpHistogram_Param_t() { - if (m_histogram != NULL) { + if (m_histogram != nullptr) { delete[] m_histogram; } } @@ -139,12 +139,12 @@ bool compare_vpHistogramPeak(vpHistogramPeak first, vpHistogramPeak second) /*! Defaut constructor for a gray level histogram. */ -vpHistogram::vpHistogram() : histogram(NULL), size(256) { init(); } +vpHistogram::vpHistogram() : histogram(nullptr), size(256) { init(); } /*! Copy constructor of a gray level histogram. */ -vpHistogram::vpHistogram(const vpHistogram &h) : histogram(NULL), size(256) +vpHistogram::vpHistogram(const vpHistogram &h) : histogram(nullptr), size(256) { init(h.size); memcpy(histogram, h.histogram, size * sizeof(unsigned)); @@ -157,7 +157,7 @@ vpHistogram::vpHistogram(const vpHistogram &h) : histogram(NULL), size(256) \sa calculate() */ -vpHistogram::vpHistogram(const vpImage &I) : histogram(NULL), size(256) +vpHistogram::vpHistogram(const vpImage &I) : histogram(nullptr), size(256) { init(); @@ -169,10 +169,10 @@ vpHistogram::vpHistogram(const vpImage &I) : histogram(NULL), siz */ vpHistogram::~vpHistogram() { - if (histogram != NULL) { + if (histogram != nullptr) { // vpTRACE("free: %p", &histogram); delete[] histogram; - histogram = NULL; + histogram = nullptr; size = 0; } } @@ -205,9 +205,9 @@ vpHistogram &vpHistogram::operator=(const vpHistogram &h) */ void vpHistogram::init(unsigned size_) { - if (histogram != NULL) { + if (histogram != nullptr) { delete[] histogram; - histogram = NULL; + histogram = nullptr; } this->size = size_; @@ -229,9 +229,9 @@ void vpHistogram::init(unsigned size_) void vpHistogram::calculate(const vpImage &I, unsigned int nbins, unsigned int nbThreads) { if (size != nbins) { - if (histogram != NULL) { + if (histogram != nullptr) { delete[] histogram; - histogram = NULL; + histogram = nullptr; } size = nbins > 256 ? 256 : (nbins > 0 ? nbins : 256); @@ -371,7 +371,7 @@ void vpHistogram::equalize(const vpImage &I, vpImage &I, const vpColor &color, */ void vpHistogram::smooth(unsigned int fsize) { - if (histogram == NULL) { + if (histogram == nullptr) { vpERROR_TRACE("Histogram array not initialised\n"); throw(vpImageException(vpImageException::notInitializedError, "Histogram array not initialised")); } @@ -484,7 +484,7 @@ void vpHistogram::smooth(unsigned int fsize) */ unsigned vpHistogram::getPeaks(std::list &peaks) { - if (histogram == NULL) { + if (histogram == nullptr) { vpERROR_TRACE("Histogram array not initialised\n"); throw(vpImageException(vpImageException::notInitializedError, "Histogram array not initialised")); } @@ -757,7 +757,7 @@ bool vpHistogram::getPeaks(unsigned char dist, vpHistogramPeak &peakl, vpHistogr */ unsigned vpHistogram::getValey(std::list &valey) { - if (histogram == NULL) { + if (histogram == nullptr) { vpERROR_TRACE("Histogram array not initialised\n"); throw(vpImageException(vpImageException::notInitializedError, "Histogram array not initialised")); } @@ -1085,7 +1085,7 @@ bool vpHistogram::write(const std::string &filename) { return (this->write(filen bool vpHistogram::write(const char *filename) { FILE *fd = fopen(filename, "w"); - if (fd == NULL) + if (fd == nullptr) return false; for (unsigned i = 0; i < size; i++) fprintf(fd, "%u %u\n", i, histogram[i]); diff --git a/modules/core/src/tools/network/vpClient.cpp b/modules/core/src/tools/network/vpClient.cpp index 55561dca5b..19d0994c8e 100644 --- a/modules/core/src/tools/network/vpClient.cpp +++ b/modules/core/src/tools/network/vpClient.cpp @@ -64,7 +64,7 @@ bool vpClient::connectToHostname(const std::string &hostname, const unsigned int // get server host information from hostname struct hostent *server = gethostbyname(hostname.c_str()); - if (server == NULL) { + if (server == nullptr) { std::string noSuchHostMessage("ERROR, "); noSuchHostMessage.append(hostname); noSuchHostMessage.append(": no such host\n"); diff --git a/modules/core/src/tools/network/vpNetwork.cpp b/modules/core/src/tools/network/vpNetwork.cpp index abfaf86dee..158c5942e3 100644 --- a/modules/core/src/tools/network/vpNetwork.cpp +++ b/modules/core/src/tools/network/vpNetwork.cpp @@ -139,7 +139,7 @@ int vpNetwork::getReceptorIndex(const char *name) { struct hostent *server = gethostbyname(name); - if (server == NULL) { + if (server == nullptr) { std::string noSuchHostMessage("ERROR, "); noSuchHostMessage.append(name); noSuchHostMessage.append(": no such host\n"); @@ -673,7 +673,7 @@ int vpNetwork::privReceiveRequestOnce() socketMax = receptor_list[i].socketFileDescriptorReceptor; } - int value = select((int)socketMax + 1, &readFileDescriptor, NULL, NULL, &tv); + int value = select((int)socketMax + 1, &readFileDescriptor, nullptr, nullptr, &tv); int numbytes = 0; if (value == -1) { @@ -757,7 +757,7 @@ int vpNetwork::privReceiveRequestOnceFrom(const unsigned int &receptorEmitting) socketMax = receptor_list[receptorEmitting].socketFileDescriptorReceptor; FD_SET((unsigned int)receptor_list[receptorEmitting].socketFileDescriptorReceptor, &readFileDescriptor); - int value = select((int)socketMax + 1, &readFileDescriptor, NULL, NULL, &tv); + int value = select((int)socketMax + 1, &readFileDescriptor, nullptr, nullptr, &tv); int numbytes = 0; if (value == -1) { if (verboseMode) diff --git a/modules/core/src/tools/network/vpServer.cpp b/modules/core/src/tools/network/vpServer.cpp index c7b92d368c..80d68105ca 100644 --- a/modules/core/src/tools/network/vpServer.cpp +++ b/modules/core/src/tools/network/vpServer.cpp @@ -228,7 +228,7 @@ bool vpServer::checkForConnections() socketMax = receptor_list[i].socketFileDescriptorReceptor; } - int value = select((int)socketMax + 1, &readFileDescriptor, NULL, NULL, &tv); + int value = select((int)socketMax + 1, &readFileDescriptor, nullptr, nullptr, &tv); if (value == -1) { // vpERROR_TRACE( "vpServer::run(), select()" ); return false; diff --git a/modules/core/src/tools/network/vpUDPClient.cpp b/modules/core/src/tools/network/vpUDPClient.cpp index fe4880f6cd..eba00e84f4 100644 --- a/modules/core/src/tools/network/vpUDPClient.cpp +++ b/modules/core/src/tools/network/vpUDPClient.cpp @@ -142,8 +142,8 @@ void vpUDPClient::init(const std::string &hostname, int port) std::stringstream ss; ss << port; struct addrinfo hints; - struct addrinfo *result = NULL; - struct addrinfo *ptr = NULL; + struct addrinfo *result = nullptr; + struct addrinfo *ptr = nullptr; memset(&hints, 0, sizeof(hints)); hints.ai_family = AF_INET; @@ -157,7 +157,7 @@ void vpUDPClient::init(const std::string &hostname, int port) throw vpException(vpException::fatalError, ss.str()); } - for (ptr = result; ptr != NULL; ptr = ptr->ai_next) { + for (ptr = result; ptr != nullptr; ptr = ptr->ai_next) { if (ptr->ai_family == AF_INET && ptr->ai_socktype == SOCK_DGRAM) { m_serverAddress = *(struct sockaddr_in *)ptr->ai_addr; break; @@ -205,7 +205,7 @@ int vpUDPClient::receive(std::string &msg, int timeoutMs) timeout.tv_sec = timeoutMs / 1000; timeout.tv_usec = (timeoutMs % 1000) * 1000; } - int retval = select((int)m_socketFileDescriptor + 1, &s, NULL, NULL, timeoutMs > 0 ? &timeout : NULL); + int retval = select((int)m_socketFileDescriptor + 1, &s, nullptr, nullptr, timeoutMs > 0 ? &timeout : nullptr); if (retval == -1) { std::cerr << "Error select!" << std::endl; @@ -251,7 +251,7 @@ int vpUDPClient::receive(void *msg, size_t len, int timeoutMs) timeout.tv_sec = timeoutMs / 1000; timeout.tv_usec = (timeoutMs % 1000) * 1000; } - int retval = select((int)m_socketFileDescriptor + 1, &s, NULL, NULL, timeoutMs > 0 ? &timeout : NULL); + int retval = select((int)m_socketFileDescriptor + 1, &s, nullptr, nullptr, timeoutMs > 0 ? &timeout : nullptr); if (retval == -1) { std::cerr << "Error select!" << std::endl; diff --git a/modules/core/src/tools/network/vpUDPServer.cpp b/modules/core/src/tools/network/vpUDPServer.cpp index b55f3efebb..42725f7db3 100644 --- a/modules/core/src/tools/network/vpUDPServer.cpp +++ b/modules/core/src/tools/network/vpUDPServer.cpp @@ -149,8 +149,8 @@ void vpUDPServer::init(const std::string &hostname, int port) std::stringstream ss; ss << port; struct addrinfo hints; - struct addrinfo *result = NULL; - struct addrinfo *ptr = NULL; + struct addrinfo *result = nullptr; + struct addrinfo *ptr = nullptr; memset(&hints, 0, sizeof(hints)); hints.ai_family = AF_INET; @@ -164,7 +164,7 @@ void vpUDPServer::init(const std::string &hostname, int port) throw vpException(vpException::fatalError, ss.str()); } - for (ptr = result; ptr != NULL; ptr = ptr->ai_next) { + for (ptr = result; ptr != nullptr; ptr = ptr->ai_next) { if (ptr->ai_family == AF_INET && ptr->ai_socktype == SOCK_DGRAM) { m_serverAddress = *(struct sockaddr_in *)ptr->ai_addr; break; @@ -220,7 +220,7 @@ int vpUDPServer::receive(std::string &msg, std::string &hostInfo, int timeoutMs) timeout.tv_sec = timeoutMs / 1000; timeout.tv_usec = (timeoutMs % 1000) * 1000; } - int retval = select((int)m_socketFileDescriptor + 1, &s, NULL, NULL, timeoutMs > 0 ? &timeout : NULL); + int retval = select((int)m_socketFileDescriptor + 1, &s, nullptr, nullptr, timeoutMs > 0 ? &timeout : nullptr); if (retval == -1) { std::cerr << "Error select!" << std::endl; @@ -258,7 +258,7 @@ int vpUDPServer::receive(std::string &msg, std::string &hostInfo, int timeoutMs) char result[INET_ADDRSTRLEN]; const char *ptr = inet_ntop(AF_INET, (void *)&m_clientAddress.sin_addr, result, sizeof(result)); - if (ptr == NULL) { + if (ptr == nullptr) { std::cerr << "inet_ntop failed with error: " << WSAGetLastError() << std::endl; } else { hostIp = result; @@ -297,8 +297,8 @@ int vpUDPServer::send(const std::string &msg, const std::string &hostname, int p std::stringstream ss; ss << port; struct addrinfo hints; - struct addrinfo *result = NULL; - struct addrinfo *ptr = NULL; + struct addrinfo *result = nullptr; + struct addrinfo *ptr = nullptr; memset(&hints, 0, sizeof(hints)); hints.ai_family = AF_INET; @@ -312,7 +312,7 @@ int vpUDPServer::send(const std::string &msg, const std::string &hostname, int p throw vpException(vpException::fatalError, ss.str()); } - for (ptr = result; ptr != NULL; ptr = ptr->ai_next) { + for (ptr = result; ptr != nullptr; ptr = ptr->ai_next) { if (ptr->ai_family == AF_INET && ptr->ai_socktype == SOCK_DGRAM) { m_clientAddress = *(struct sockaddr_in *)ptr->ai_addr; break; diff --git a/modules/core/src/tools/serial/vpSerial.cpp b/modules/core/src/tools/serial/vpSerial.cpp index ac6f6273fc..a36e5e16f1 100644 --- a/modules/core/src/tools/serial/vpSerial.cpp +++ b/modules/core/src/tools/serial/vpSerial.cpp @@ -267,7 +267,7 @@ bool vpSerial::read(char *c, long timeout_s) FD_ZERO(&readfds); FD_SET(static_cast(m_fd), &readfds); - int ret = select(FD_SETSIZE, &readfds, (fd_set *)NULL, (fd_set *)NULL, &timeout); + int ret = select(FD_SETSIZE, &readfds, (fd_set *)nullptr, (fd_set *)nullptr, &timeout); if (ret < 0) { throw(vpException(vpException::fatalError, "Serial i/o exception")); diff --git a/modules/core/src/tools/xml/vpXmlParser.cpp b/modules/core/src/tools/xml/vpXmlParser.cpp index 7ac5cee6cf..8c203293bb 100644 --- a/modules/core/src/tools/xml/vpXmlParser.cpp +++ b/modules/core/src/tools/xml/vpXmlParser.cpp @@ -96,7 +96,7 @@ vpXmlParser::vpXmlParser(const vpXmlParser &_twin) : nodeMap(_twin.nodeMap), mai */ char *vpXmlParser::xmlReadCharChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read char*"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -116,7 +116,7 @@ char *vpXmlParser::xmlReadCharChild(xmlDocPtr doc, xmlNodePtr node) std::string vpXmlParser::xmlReadStringChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read std::string"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -140,7 +140,7 @@ std::string vpXmlParser::xmlReadStringChild(xmlDocPtr doc, xmlNodePtr node) */ int vpXmlParser::xmlReadIntChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read int"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -174,7 +174,7 @@ int vpXmlParser::xmlReadIntChild(xmlDocPtr doc, xmlNodePtr node) */ unsigned int vpXmlParser::xmlReadUnsignedIntChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read unsigned int"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -208,7 +208,7 @@ unsigned int vpXmlParser::xmlReadUnsignedIntChild(xmlDocPtr doc, xmlNodePtr node */ double vpXmlParser::xmlReadDoubleChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read double"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -241,7 +241,7 @@ double vpXmlParser::xmlReadDoubleChild(xmlDocPtr doc, xmlNodePtr node) */ float vpXmlParser::xmlReadFloatChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read float"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -278,7 +278,7 @@ float vpXmlParser::xmlReadFloatChild(xmlDocPtr doc, xmlNodePtr node) */ bool vpXmlParser::xmlReadBoolChild(xmlDocPtr doc, xmlNodePtr node) { - if (node->xmlChildrenNode == NULL) { + if (node->xmlChildrenNode == nullptr) { std::string errorMsg = "Empty node " + std::string((char *)node->name) + ", cannot read bool"; std::cerr << errorMsg << std::endl; throw vpException(vpException::fatalError, errorMsg); @@ -303,7 +303,7 @@ bool vpXmlParser::xmlReadBoolChild(xmlDocPtr doc, xmlNodePtr node) void vpXmlParser::xmlWriteCharChild(xmlNodePtr node, const char *label, const char *value) { xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)value); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)value); xmlAddChild(node, tmp); } @@ -317,7 +317,7 @@ void vpXmlParser::xmlWriteCharChild(xmlNodePtr node, const char *label, const ch void vpXmlParser::xmlWriteStringChild(xmlNodePtr node, const char *label, const std::string &value) { xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)value.c_str()); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)value.c_str()); xmlAddChild(node, tmp); } @@ -333,7 +333,7 @@ void vpXmlParser::xmlWriteIntChild(xmlNodePtr node, const char *label, int value char str[100]; snprintf(str, 100, "%d", value); xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)str); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)str); xmlAddChild(node, tmp); } @@ -349,7 +349,7 @@ void vpXmlParser::xmlWriteUnsignedIntChild(xmlNodePtr node, const char *label, u char str[100]; snprintf(str, 100, "%u", value); xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)str); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)str); xmlAddChild(node, tmp); } @@ -365,7 +365,7 @@ void vpXmlParser::xmlWriteDoubleChild(xmlNodePtr node, const char *label, double char str[100]; snprintf(str, 100, "%lf", value); xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)str); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)str); xmlAddChild(node, tmp); } @@ -381,7 +381,7 @@ void vpXmlParser::xmlWriteFloatChild(xmlNodePtr node, const char *label, float v char str[100]; snprintf(str, 100, "%f", value); xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)str); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)str); xmlAddChild(node, tmp); } @@ -397,7 +397,7 @@ void vpXmlParser::xmlWriteBoolChild(xmlNodePtr node, const char *label, bool val char str[2]; snprintf(str, 2, "%d", (int)value); xmlNodePtr tmp; - tmp = xmlNewChild(node, NULL, (xmlChar *)label, (xmlChar *)str); + tmp = xmlNewChild(node, nullptr, (xmlChar *)label, (xmlChar *)str); xmlAddChild(node, tmp); } @@ -421,13 +421,13 @@ void vpXmlParser::parse(const std::string &filename) xmlNodePtr root_node; doc = xmlParseFile(filename.c_str()); - if (doc == NULL) { + if (doc == nullptr) { vpERROR_TRACE("cannot open file"); throw vpException(vpException::ioError, "cannot open file"); } root_node = xmlDocGetRootElement(doc); - if (root_node == NULL) { + if (root_node == nullptr) { vpERROR_TRACE("cannot get root element"); throw vpException(vpException::ioError, "cannot get root element"); } @@ -452,10 +452,10 @@ void vpXmlParser::save(const std::string &filename, bool append) xmlDocPtr doc; xmlNodePtr root_node; - doc = xmlReadFile(filename.c_str(), NULL, XML_PARSE_NOWARNING + XML_PARSE_NOERROR + XML_PARSE_NOBLANKS); - if (doc == NULL) { + doc = xmlReadFile(filename.c_str(), nullptr, XML_PARSE_NOWARNING + XML_PARSE_NOERROR + XML_PARSE_NOBLANKS); + if (doc == nullptr) { doc = xmlNewDoc((xmlChar *)"1.0"); - root_node = xmlNewNode(NULL, (xmlChar *)main_tag.c_str()); + root_node = xmlNewNode(nullptr, (xmlChar *)main_tag.c_str()); xmlDocSetRootElement(doc, root_node); } else { if (!append) { @@ -464,13 +464,13 @@ void vpXmlParser::save(const std::string &filename, bool append) throw vpException(vpException::ioError, "Cannot remove existing xml file"); doc = xmlNewDoc((xmlChar *)"1.0"); - root_node = xmlNewNode(NULL, (xmlChar *)main_tag.c_str()); + root_node = xmlNewNode(nullptr, (xmlChar *)main_tag.c_str()); xmlDocSetRootElement(doc, root_node); } } root_node = xmlDocGetRootElement(doc); - if (root_node == NULL) { + if (root_node == nullptr) { vpERROR_TRACE("problem to get the root node"); throw vpException(vpException::ioError, "problem to get the root node"); } diff --git a/modules/core/src/tracking/moments/vpMoment.cpp b/modules/core/src/tracking/moments/vpMoment.cpp index 866ffe60eb..dced3cf428 100644 --- a/modules/core/src/tracking/moments/vpMoment.cpp +++ b/modules/core/src/tracking/moments/vpMoment.cpp @@ -48,7 +48,7 @@ /*! Default constructor */ -vpMoment::vpMoment() : object(NULL), moments(NULL), values() {} +vpMoment::vpMoment() : object(nullptr), moments(nullptr), values() {} /*! Links the moment to a database of moment primitives. diff --git a/modules/core/test/image-with-dataset/testConversion.cpp b/modules/core/test/image-with-dataset/testConversion.cpp index a61f87d6f8..3fc667e281 100644 --- a/modules/core/test/image-with-dataset/testConversion.cpp +++ b/modules/core/test/image-with-dataset/testConversion.cpp @@ -140,7 +140,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op nbIterations = atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, opath, user, nbIterations); + usage(argv[0], nullptr, ipath, opath, user, nbIterations); return false; case 'c': @@ -155,7 +155,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user, nbIterations); + usage(argv[0], nullptr, ipath, opath, user, nbIterations); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -215,7 +215,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username, nbIterations); + usage(argv[0], nullptr, ipath, opt_opath, username, nbIterations); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -236,7 +236,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username, nbIterations); + usage(argv[0], nullptr, ipath, opt_opath, username, nbIterations); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -307,7 +307,7 @@ int main(int argc, const char **argv) int flags = CV_LOAD_IMAGE_COLOR; #endif imageMat = cv::imread(filename, flags); // Force to a three channel BGR color image. - if (imageMat.data == NULL) { + if (imageMat.data == nullptr) { std::cout << " Cannot read image: " << filename << std::endl; return EXIT_FAILURE; } @@ -326,7 +326,7 @@ int main(int argc, const char **argv) flags = CV_LOAD_IMAGE_GRAYSCALE; #endif imageMat = cv::imread(filename, flags); // Forced to grayscale. - if (imageMat.data == NULL) { + if (imageMat.data == nullptr) { std::cout << " Cannot read image: " << filename << std::endl; return EXIT_FAILURE; } @@ -350,7 +350,7 @@ int main(int argc, const char **argv) flags = CV_LOAD_IMAGE_COLOR; #endif imageMat = cv::imread(filename, flags); // Force to a three channel BGR color image. - if (imageMat.data == NULL) { + if (imageMat.data == nullptr) { std::cout << " Cannot read image: " << filename << std::endl; return EXIT_FAILURE; } @@ -370,7 +370,7 @@ int main(int argc, const char **argv) flags = CV_LOAD_IMAGE_GRAYSCALE; #endif imageMat = cv::imread(filename, flags); - if (imageMat.data == NULL) { + if (imageMat.data == nullptr) { std::cout << " Cannot read image: " << filename << std::endl; return EXIT_FAILURE; } @@ -439,10 +439,10 @@ int main(int argc, const char **argv) std::cout << " Load " << filename << std::endl; vpImageIo::read(Ic, filename); vpImage R, G, B, a; - vpImageConvert::split(Ic, &R, NULL, &B); + vpImageConvert::split(Ic, &R, nullptr, &B); chrono.start(); for (int iteration = 0; iteration < nbIterations; iteration++) { - vpImageConvert::split(Ic, &R, NULL, &B); + vpImageConvert::split(Ic, &R, nullptr, &B); } chrono.stop(); @@ -494,7 +494,7 @@ int main(int argc, const char **argv) vpImage I_saturation(&saturation.front(), h, w); vpImage I_value(&value.front(), h, w); vpImage I_HSV; - vpImageConvert::merge(&I_hue, &I_saturation, &I_value, NULL, I_HSV); + vpImageConvert::merge(&I_hue, &I_saturation, &I_value, nullptr, I_HSV); filename = vpIoTools::createFilePath(opath, "Klimt_HSV.ppm"); std::cout << " Resulting image saved in: " << filename << std::endl; diff --git a/modules/core/test/image-with-dataset/testCrop.cpp b/modules/core/test/image-with-dataset/testCrop.cpp index 9f64551516..75333030ae 100644 --- a/modules/core/test/image-with-dataset/testCrop.cpp +++ b/modules/core/test/image-with-dataset/testCrop.cpp @@ -130,7 +130,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -147,7 +147,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -205,7 +205,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -226,7 +226,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/image-with-dataset/testCropAdvanced.cpp b/modules/core/test/image-with-dataset/testCropAdvanced.cpp index 224ba1485a..7e748ead18 100644 --- a/modules/core/test/image-with-dataset/testCropAdvanced.cpp +++ b/modules/core/test/image-with-dataset/testCropAdvanced.cpp @@ -122,7 +122,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -139,7 +139,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -196,7 +196,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -217,7 +217,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/image-with-dataset/testImageComparison.cpp b/modules/core/test/image-with-dataset/testImageComparison.cpp index 8aa597c41e..e5782b9651 100644 --- a/modules/core/test/image-with-dataset/testImageComparison.cpp +++ b/modules/core/test/image-with-dataset/testImageComparison.cpp @@ -107,7 +107,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath) ipath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -124,7 +124,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -177,7 +177,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/image-with-dataset/testImageFilter.cpp b/modules/core/test/image-with-dataset/testImageFilter.cpp index 408144adee..51315e8b0e 100644 --- a/modules/core/test/image-with-dataset/testImageFilter.cpp +++ b/modules/core/test/image-with-dataset/testImageFilter.cpp @@ -114,7 +114,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp ppath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -131,7 +131,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp b/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp index 37ce35b37b..7b49cb53db 100644 --- a/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp +++ b/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp @@ -89,7 +89,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath) ipath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -106,7 +106,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -181,7 +181,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -226,8 +226,8 @@ int main(int argc, const char **argv) vpImagePoint max_loc, max_loc_gold; double max_correlation = -1.0, max_correlation_gold = -1.0; - I_score.getMinMaxLoc(NULL, &max_loc, NULL, &max_correlation); - I_score_gold.getMinMaxLoc(NULL, &max_loc_gold, NULL, &max_correlation_gold); + I_score.getMinMaxLoc(nullptr, &max_loc, nullptr, &max_correlation); + I_score_gold.getMinMaxLoc(nullptr, &max_loc_gold, nullptr, &max_correlation_gold); std::cout << "Compare regular and SSE version of vpImageTools::normalizedCorrelation()" << std::endl; std::cout << "vpImageTools::normalizedCorrelation(): " << max_correlation << " ; " << t << " ms" << std::endl; diff --git a/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp b/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp index ed11ce5bc1..ffab07fb18 100644 --- a/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp +++ b/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp @@ -95,7 +95,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click, bo ipath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; case 't': @@ -117,7 +117,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click, bo if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -242,7 +242,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -297,7 +297,7 @@ int main(int argc, const char **argv) vpImagePoint max_loc; double max_correlation = -1.0; - I_score.getMinMaxLoc(NULL, &max_loc, NULL, &max_correlation); + I_score.getMinMaxLoc(nullptr, &max_loc, nullptr, &max_correlation); t_proc = vpTime::measureTimeMs() - t_proc; benchmark_vec.push_back(t_proc); diff --git a/modules/core/test/image-with-dataset/testIoPGM.cpp b/modules/core/test/image-with-dataset/testIoPGM.cpp index a1077b1b29..b6dcb78ee8 100644 --- a/modules/core/test/image-with-dataset/testIoPGM.cpp +++ b/modules/core/test/image-with-dataset/testIoPGM.cpp @@ -124,7 +124,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -141,7 +141,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -199,7 +199,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -220,7 +220,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/image-with-dataset/testIoPPM.cpp b/modules/core/test/image-with-dataset/testIoPPM.cpp index d4195abfa9..363e480708 100644 --- a/modules/core/test/image-with-dataset/testIoPPM.cpp +++ b/modules/core/test/image-with-dataset/testIoPPM.cpp @@ -126,7 +126,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -143,7 +143,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -201,7 +201,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -222,7 +222,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/image-with-dataset/testPerformanceLUT.cpp b/modules/core/test/image-with-dataset/testPerformanceLUT.cpp index 1508bea06e..0705fbebf4 100644 --- a/modules/core/test/image-with-dataset/testPerformanceLUT.cpp +++ b/modules/core/test/image-with-dataset/testPerformanceLUT.cpp @@ -125,7 +125,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op nbThreads = (unsigned int)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -142,7 +142,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -290,7 +290,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -311,7 +311,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/image-with-dataset/testReadImage.cpp b/modules/core/test/image-with-dataset/testReadImage.cpp index 0e5325085d..13fecb8b98 100644 --- a/modules/core/test/image-with-dataset/testReadImage.cpp +++ b/modules/core/test/image-with-dataset/testReadImage.cpp @@ -121,7 +121,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp ppath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -138,7 +138,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/image-with-dataset/testUndistortImage.cpp b/modules/core/test/image-with-dataset/testUndistortImage.cpp index 49690b4f9c..9f63d5687f 100644 --- a/modules/core/test/image-with-dataset/testUndistortImage.cpp +++ b/modules/core/test/image-with-dataset/testUndistortImage.cpp @@ -149,7 +149,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op scale = atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; case 'c': @@ -164,7 +164,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -230,7 +230,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -251,7 +251,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/math/testMatrixDeterminant.cpp b/modules/core/test/math/testMatrixDeterminant.cpp index cdb3ab20dd..77ed348f5e 100644 --- a/modules/core/test/math/testMatrixDeterminant.cpp +++ b/modules/core/test/math/testMatrixDeterminant.cpp @@ -118,7 +118,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; case 'n': @@ -157,7 +157,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/math/testMatrixInverse.cpp b/modules/core/test/math/testMatrixInverse.cpp index 7ce8fa88ba..745fc88c98 100644 --- a/modules/core/test/math/testMatrixInverse.cpp +++ b/modules/core/test/math/testMatrixInverse.cpp @@ -126,7 +126,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; case 'n': @@ -165,7 +165,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/math/testMatrixPseudoInverse.cpp b/modules/core/test/math/testMatrixPseudoInverse.cpp index 5314f4ba7e..5ca14afa35 100644 --- a/modules/core/test/math/testMatrixPseudoInverse.cpp +++ b/modules/core/test/math/testMatrixPseudoInverse.cpp @@ -123,7 +123,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; case 'n': @@ -162,7 +162,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/math/testRobust.cpp b/modules/core/test/math/testRobust.cpp index fb63016a9f..86697b5640 100644 --- a/modules/core/test/math/testRobust.cpp +++ b/modules/core/test/math/testRobust.cpp @@ -113,7 +113,7 @@ bool getOptions(int argc, const char **argv, std::string &ofilename) ofilename = optarg_; break; case 'h': - usage(argv[0], NULL, ofilename); + usage(argv[0], nullptr, ofilename); return false; break; @@ -129,7 +129,7 @@ bool getOptions(int argc, const char **argv, std::string &ofilename) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ofilename); + usage(argv[0], nullptr, ofilename); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -163,7 +163,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(ofilename); } catch (...) { - usage(argv[0], NULL, ofilename); + usage(argv[0], nullptr, ofilename); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << ofilename << std::endl; std::cerr << " Check your -o " << ofilename << " option " << std::endl; @@ -186,7 +186,7 @@ int main(int argc, const char **argv) std::cout << "Create file: " << ofilename << std::endl; f.open(ofilename.c_str()); if (f.fail()) { - usage(argv[0], NULL, ofilename); + usage(argv[0], nullptr, ofilename); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create the file: " << ofilename << std::endl; std::cerr << " Check your -o " << ofilename << " option " << std::endl; diff --git a/modules/core/test/math/testSvd.cpp b/modules/core/test/math/testSvd.cpp index 546fa194f2..3c7f9420da 100644 --- a/modules/core/test/math/testSvd.cpp +++ b/modules/core/test/math/testSvd.cpp @@ -124,7 +124,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned switch (c) { case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; case 'n': @@ -163,7 +163,7 @@ bool getOptions(int argc, const char **argv, unsigned int &nb_matrices, unsigned if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/tools/geometry/testPolygon.cpp b/modules/core/test/tools/geometry/testPolygon.cpp index 132eda4f40..784cbccfc7 100644 --- a/modules/core/test/tools/geometry/testPolygon.cpp +++ b/modules/core/test/tools/geometry/testPolygon.cpp @@ -118,7 +118,7 @@ bool getOptions(int argc, const char **argv, bool &opt_display, bool &opt_click, method = atoi(optarg_); break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -131,7 +131,7 @@ bool getOptions(int argc, const char **argv, bool &opt_display, bool &opt_click, if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp index ef22227daf..6dfb62ce80 100644 --- a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp +++ b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp @@ -118,7 +118,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, unsigned int &n nbThreads = (unsigned int)atoi(optarg_); break; case 'h': - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); return false; break; @@ -135,7 +135,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, unsigned int &n if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -238,7 +238,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath); + usage(argv[0], nullptr, ipath); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/core/test/tools/threading/testThread2.cpp b/modules/core/test/tools/threading/testThread2.cpp index 5fba1d2687..10ed60cfc5 100644 --- a/modules/core/test/tools/threading/testThread2.cpp +++ b/modules/core/test/tools/threading/testThread2.cpp @@ -144,7 +144,7 @@ int main() { unsigned int nb_threads = 4; unsigned int size = 1000007; - srand((unsigned int)time(NULL)); + srand((unsigned int)time(nullptr)); vpColVector v1(size), v2(size); for (unsigned int i = 0; i < size; i++) { diff --git a/modules/core/test/tools/xml/testXmlParser.cpp b/modules/core/test/tools/xml/testXmlParser.cpp index 5dbcecbc5f..5c667d327d 100644 --- a/modules/core/test/tools/xml/testXmlParser.cpp +++ b/modules/core/test/tools/xml/testXmlParser.cpp @@ -120,7 +120,7 @@ vpExampleDataParser::vpExampleDataParser() : m_range(0.), m_step(0), m_size_filt */ void vpExampleDataParser::readMainClass(xmlDocPtr doc, xmlNodePtr node) { - for (xmlNodePtr dataNode = node->xmlChildrenNode; dataNode != NULL; dataNode = dataNode->next) { + for (xmlNodePtr dataNode = node->xmlChildrenNode; dataNode != nullptr; dataNode = dataNode->next) { if (dataNode->type == XML_ELEMENT_NODE) { std::map::iterator iter_data = this->nodeMap.find((char *)dataNode->name); if (iter_data != nodeMap.end()) { @@ -228,7 +228,7 @@ bool getOptions(int argc, const char **argv, std::string &opath, const std::stri opath = optarg_; break; case 'h': - usage(argv[0], NULL, opath, user); + usage(argv[0], nullptr, opath, user); return false; break; @@ -245,7 +245,7 @@ bool getOptions(int argc, const char **argv, std::string &opath, const std::stri if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, opath, user); + usage(argv[0], nullptr, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -301,7 +301,7 @@ int main(int argc, const char **argv) vpIoTools::makeDirectory(dirname); } catch (...) { - usage(argv[0], NULL, opath, username); + usage(argv[0], nullptr, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << dirname << std::endl; std::cerr << " Check your -o " << opath << " option " << std::endl; diff --git a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h index 0bb54ee988..e440dac32f 100644 --- a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h +++ b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h @@ -254,8 +254,8 @@ class VISP_EXPORT vpDetectorAprilTag : public vpDetectorBase bool detect(const vpImage &I) override; bool detect(const vpImage &I, double tagSize, const vpCameraParameters &cam, - std::vector &cMo_vec, std::vector *cMo_vec2 = NULL, - std::vector *projErrors = NULL, std::vector *projErrors2 = NULL); + std::vector &cMo_vec, std::vector *cMo_vec2 = nullptr, + std::vector *projErrors = nullptr, std::vector *projErrors2 = nullptr); void displayFrames(const vpImage &I, const std::vector &cMo_vec, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness = 1) const; @@ -268,7 +268,7 @@ class VISP_EXPORT vpDetectorAprilTag : public vpDetectorBase const vpColor &color = vpColor::none, unsigned int thickness = 1) const; bool getPose(size_t tagIndex, double tagSize, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, - vpHomogeneousMatrix *cMo2 = NULL, double *projError = NULL, double *projError2 = NULL); + vpHomogeneousMatrix *cMo2 = nullptr, double *projError = nullptr, double *projError2 = nullptr); /*! * Return the pose estimation method. diff --git a/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp b/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp index 5d3e28d47b..c71573fe15 100644 --- a/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp +++ b/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp @@ -67,7 +67,7 @@ bool vpDetectorDataMatrixCode::detect(const vpImage &I) DmtxImage *img; DmtxMessage *msg; - DmtxTime *dmtx_timeout = NULL; + DmtxTime *dmtx_timeout = nullptr; if (m_timeout_ms) { dmtx_timeout = new DmtxTime; *dmtx_timeout = dmtxTimeNow(); @@ -75,18 +75,18 @@ bool vpDetectorDataMatrixCode::detect(const vpImage &I) } img = dmtxImageCreate(I.bitmap, (int)I.getWidth(), (int)I.getHeight(), DmtxPack8bppK); - assert(img != NULL); + assert(img != nullptr); dec = dmtxDecodeCreate(img, 1); - assert(dec != NULL); + assert(dec != nullptr); bool end = false; do { reg = dmtxRegionFindNext(dec, dmtx_timeout); - if (reg != NULL) { + if (reg != nullptr) { msg = dmtxDecodeMatrixRegion(dec, reg, DmtxUndefined); - if (msg != NULL) { + if (msg != nullptr) { std::vector polygon; diff --git a/modules/detection/src/barcode/vpDetectorQRCode.cpp b/modules/detection/src/barcode/vpDetectorQRCode.cpp index fd8db87ddd..81c904b6fd 100644 --- a/modules/detection/src/barcode/vpDetectorQRCode.cpp +++ b/modules/detection/src/barcode/vpDetectorQRCode.cpp @@ -84,7 +84,7 @@ bool vpDetectorQRCode::detect(const vpImage &I) } // clean up - img.set_data(NULL, 0); + img.set_data(nullptr, 0); return detected; } diff --git a/modules/detection/src/tag/vpDetectorAprilTag.cpp b/modules/detection/src/tag/vpDetectorAprilTag.cpp index 984ce3182f..b8feb4efdc 100644 --- a/modules/detection/src/tag/vpDetectorAprilTag.cpp +++ b/modules/detection/src/tag/vpDetectorAprilTag.cpp @@ -65,7 +65,7 @@ class vpDetectorAprilTag::Impl { public: Impl(const vpAprilTagFamily &tagFamily, const vpPoseEstimationMethod &method) - : m_poseEstimationMethod(method), m_tagsId(), m_tagFamily(tagFamily), m_td(NULL), m_tf(NULL), m_detections(NULL), + : m_poseEstimationMethod(method), m_tagsId(), m_tagFamily(tagFamily), m_td(nullptr), m_tf(nullptr), m_detections(nullptr), m_zAlignedWithCameraFrame(false) { switch (m_tagFamily) { @@ -134,8 +134,8 @@ class vpDetectorAprilTag::Impl } Impl(const Impl &o) - : m_poseEstimationMethod(o.m_poseEstimationMethod), m_tagsId(o.m_tagsId), m_tagFamily(o.m_tagFamily), m_td(NULL), - m_tf(NULL), m_detections(NULL), m_zAlignedWithCameraFrame(o.m_zAlignedWithCameraFrame) + : m_poseEstimationMethod(o.m_poseEstimationMethod), m_tagsId(o.m_tagsId), m_tagFamily(o.m_tagFamily), m_td(nullptr), + m_tf(nullptr), m_detections(nullptr), m_zAlignedWithCameraFrame(o.m_zAlignedWithCameraFrame) { switch (m_tagFamily) { case TAG_36h11: @@ -201,7 +201,7 @@ class vpDetectorAprilTag::Impl m_mapOfCorrespondingPoseMethods[DEMENTHON_VIRTUAL_VS] = vpPose::DEMENTHON; m_mapOfCorrespondingPoseMethods[LAGRANGE_VIRTUAL_VS] = vpPose::LAGRANGE; - if (o.m_detections != NULL) { + if (o.m_detections != nullptr) { m_detections = apriltag_detections_copy(o.m_detections); } } @@ -272,7 +272,7 @@ class vpDetectorAprilTag::Impl if (m_detections) { apriltag_detections_destroy(m_detections); - m_detections = NULL; + m_detections = nullptr; } } @@ -306,7 +306,7 @@ class vpDetectorAprilTag::Impl } #endif - const bool computePose = (cMo_vec != NULL); + const bool computePose = (cMo_vec != nullptr); image_u8_t im = {/*.width =*/(int32_t)I.getWidth(), /*.height =*/(int32_t)I.getHeight(), @@ -315,7 +315,7 @@ class vpDetectorAprilTag::Impl if (m_detections) { apriltag_detections_destroy(m_detections); - m_detections = NULL; + m_detections = nullptr; } m_detections = apriltag_detector_detect(m_td, &im); @@ -359,8 +359,8 @@ class vpDetectorAprilTag::Impl if (computePose) { vpHomogeneousMatrix cMo, cMo2; double err1, err2; - if (getPose(static_cast(i), tagSize, cam, cMo, cMo_vec2 ? &cMo2 : NULL, projErrors ? &err1 : NULL, - projErrors2 ? &err2 : NULL)) { + if (getPose(static_cast(i), tagSize, cam, cMo, cMo_vec2 ? &cMo2 : nullptr, projErrors ? &err1 : nullptr, + projErrors2 ? &err2 : nullptr)) { cMo_vec->push_back(cMo); if (cMo_vec2) { cMo_vec2->push_back(cMo2); @@ -446,7 +446,7 @@ class vpDetectorAprilTag::Impl bool getPose(size_t tagIndex, double tagSize, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, vpHomogeneousMatrix *cMo2, double *projErrors, double *projErrors2) { - if (m_detections == NULL) { + if (m_detections == nullptr) { throw(vpException(vpException::fatalError, "Cannot get tag index=%d pose: detection empty", tagIndex)); } if (m_tagFamily == TAG_36ARTOOLKIT) { @@ -849,7 +849,7 @@ bool vpDetectorAprilTag::detect(const vpImage &I) std::vector cMo_vec; const double tagSize = 1.0; bool detected = m_impl->detect(I, tagSize, m_defaultCam, m_polygon, m_message, m_displayTag, m_displayTagColor, - m_displayTagThickness, NULL, NULL, NULL, NULL); + m_displayTagThickness, nullptr, nullptr, nullptr, nullptr); m_nb_objects = m_message.size(); return detected; diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index b977619fbf..ddc2cdab4b 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -170,9 +170,9 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay // vpDisplayOpenCV(const vpDisplayOpenCV &) // : vpDisplay(), // #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - // background(NULL), col(NULL), cvcolor(), font(NULL), + // background(nullptr), col(nullptr), cvcolor(), font(nullptr), // #else - // background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), + // background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), // fontScale(0.8f), // #endif // fontHeight(10), x_move(0), y_move(0) , move(false), diff --git a/modules/gui/include/visp3/gui/vpDisplayWin32.h b/modules/gui/include/visp3/gui/vpDisplayWin32.h index 47a8d8611a..437a803b23 100644 --- a/modules/gui/include/visp3/gui/vpDisplayWin32.h +++ b/modules/gui/include/visp3/gui/vpDisplayWin32.h @@ -112,7 +112,7 @@ class VISP_EXPORT vpDisplayWin32 : public vpDisplay friend void vpCreateWindow(threadParam *param); public: - explicit vpDisplayWin32(vpWin32Renderer *rend = NULL); + explicit vpDisplayWin32(vpWin32Renderer *rend = nullptr); vpDisplayWin32(vpImage &I, int winx = -1, int winy = -1, const std::string &title = ""); diff --git a/modules/gui/include/visp3/gui/vpDisplayX.h b/modules/gui/include/visp3/gui/vpDisplayX.h index feaadfc8bb..3d2b2d3b55 100644 --- a/modules/gui/include/visp3/gui/vpDisplayX.h +++ b/modules/gui/include/visp3/gui/vpDisplayX.h @@ -129,9 +129,9 @@ class VISP_EXPORT vpDisplayX : public vpDisplay // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpDisplayX(const vpDisplayX &) - // : vpDisplay(), display(NULL), window(), Ximage(NULL), lut(), + // : vpDisplay(), display(nullptr), window(), Ximage(nullptr), lut(), // context(), screen(), event(), pixmap(), - // x_color(NULL), screen_depth(8), xcolor(), values(), + // x_color(nullptr), screen_depth(8), xcolor(), values(), // ximage_data_init(false), RMask(0), GMask(0), BMask(0), RShift(0), // GShift(0), BShift(0) // { diff --git a/modules/gui/include/visp3/gui/vpPlot.h b/modules/gui/include/visp3/gui/vpPlot.h index 0ec40b738f..ffd1dbb128 100644 --- a/modules/gui/include/visp3/gui/vpPlot.h +++ b/modules/gui/include/visp3/gui/vpPlot.h @@ -125,7 +125,7 @@ class VISP_EXPORT vpPlot // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpPlot(const vpPlot &) - // : I(), display(NULL), graphNbr(0), graphList(NULL), margei(0), + // : I(), display(nullptr), graphNbr(0), graphList(nullptr), margei(0), // margej(0), // factori(0), factorj(0) // { diff --git a/modules/gui/include/visp3/gui/vpPlotGraph.h b/modules/gui/include/visp3/gui/vpPlotGraph.h index 4e8b0e01d8..935e4c15f9 100644 --- a/modules/gui/include/visp3/gui/vpPlotGraph.h +++ b/modules/gui/include/visp3/gui/vpPlotGraph.h @@ -143,7 +143,7 @@ class vpPlotGraph // : xorg(0.), yorg(0.), zoomx(1.), zoomy(1.), xmax(10), ymax(10), // xmin(0), ymin(-10), // xdelt(1), ydelt(1), gridx(true), gridy(true), gridColor(), - // curveNbr(1), curveList(NULL), scaleInitialized(false), + // curveNbr(1), curveList(nullptr), scaleInitialized(false), // firstPoint(true), nbDivisionx(10), nbDivisiony(10), topLeft(), // width(0), height(0), graphZone(), dTopLeft(), dWidth(0), // dHeight(0), dGraphZone(), dTopLeft3D(), dGraphZone3D(), cam(), diff --git a/modules/gui/include/visp3/gui/vpWin32Window.h b/modules/gui/include/visp3/gui/vpWin32Window.h index e36934dadc..1e97ad6e0f 100644 --- a/modules/gui/include/visp3/gui/vpWin32Window.h +++ b/modules/gui/include/visp3/gui/vpWin32Window.h @@ -112,7 +112,7 @@ class VISP_EXPORT vpWin32Window vpWin32Renderer *renderer; public: - explicit vpWin32Window(vpWin32Renderer *rend = NULL); + explicit vpWin32Window(vpWin32Renderer *rend = nullptr); virtual ~vpWin32Window(); HWND getHWnd() { return hWnd; } diff --git a/modules/gui/src/display/vpDisplayGTK.cpp b/modules/gui/src/display/vpDisplayGTK.cpp index e9a849c8d7..7e4fa7da78 100644 --- a/modules/gui/src/display/vpDisplayGTK.cpp +++ b/modules/gui/src/display/vpDisplayGTK.cpp @@ -72,10 +72,10 @@ class vpDisplayGTK::Impl { public: Impl() - : m_widget(NULL), m_background(NULL), m_gc(NULL), m_blue(), m_red(), m_yellow(), m_green(), m_cyan(), m_orange(), + : m_widget(nullptr), m_background(nullptr), m_gc(nullptr), m_blue(), m_red(), m_yellow(), m_green(), m_cyan(), m_orange(), m_white(), m_black(), m_gdkcolor(), m_lightBlue(), m_darkBlue(), m_lightRed(), m_darkRed(), m_lightGreen(), - m_darkGreen(), m_purple(), m_lightGray(), m_gray(), m_darkGray(), m_colormap(NULL), m_font(NULL), m_vectgtk(NULL), - m_col(NULL) + m_darkGreen(), m_purple(), m_lightGray(), m_gray(), m_darkGray(), m_colormap(nullptr), m_font(nullptr), m_vectgtk(nullptr), + m_col(nullptr) { } ~Impl() { } @@ -86,7 +86,7 @@ class vpDisplayGTK::Impl gint height = static_cast(win_height); /* Initialisation of the gdk et gdk_rgb library */ - int *argc = NULL; + int *argc = nullptr; char **argv; gtk_init(argc, &argv); @@ -190,9 +190,9 @@ class vpDisplayGTK::Impl // Try to load a default font m_font = gdk_font_load("-*-times-medium-r-normal-*-16-*-*-*-*-*-*-*"); - if (m_font == NULL) + if (m_font == nullptr) m_font = gdk_font_load("-*-courier-bold-r-normal-*-*-140-*-*-*-*-*-*"); - if (m_font == NULL) + if (m_font == nullptr) m_font = gdk_font_load("-*-courier 10 pitch-medium-r-normal-*-16-*-*-*-*-*-*-*"); if (!title.empty()) @@ -257,16 +257,16 @@ class vpDisplayGTK::Impl void closeDisplay() { - if (m_col != NULL) { + if (m_col != nullptr) { delete[] m_col; - m_col = NULL; + m_col = nullptr; } - if (m_widget != NULL) { + if (m_widget != nullptr) { gdk_window_hide(m_widget->window); gdk_window_destroy(m_widget->window); gtk_widget_destroy(m_widget); - m_widget = NULL; + m_widget = nullptr; } } @@ -287,7 +287,7 @@ class vpDisplayGTK::Impl gdk_colormap_alloc_color(m_colormap, &m_gdkcolor, FALSE, TRUE); gdk_gc_set_foreground(m_gc, &m_gdkcolor); } - if (m_font != NULL) + if (m_font != nullptr) gdk_draw_string(m_background, m_font, m_gc, vpMath::round(ip.get_u() / scale), vpMath::round(ip.get_v() / scale), (const gchar *)text); else @@ -409,7 +409,7 @@ class vpDisplayGTK::Impl { bool ret = false; do { - GdkEvent *ev = NULL; + GdkEvent *ev = nullptr; while ((ev = gdk_event_get())) { if (ev->any.window == m_widget->window && ev->type == event_type) { double u = ((GdkEventButton *)ev)->x; @@ -473,8 +473,8 @@ class vpDisplayGTK::Impl bool ret = false; int cpt = 0; do { - GdkEvent *ev = NULL; - while ((ev = gdk_event_get()) != NULL) { + GdkEvent *ev = nullptr; + while ((ev = gdk_event_get()) != nullptr) { cpt++; if (ev->any.window == m_widget->window && ev->type == GDK_KEY_PRESS) { @@ -494,7 +494,7 @@ class vpDisplayGTK::Impl bool getPointerMotionEvent(vpImagePoint &ip, unsigned int scale) { bool ret = false; - GdkEvent *ev = NULL; + GdkEvent *ev = nullptr; if ((ev = gdk_event_get())) { if (ev->any.window == m_widget->window && ev->type == GDK_MOTION_NOTIFY) { double u = ((GdkEventMotion *)ev)->x; @@ -512,7 +512,7 @@ class vpDisplayGTK::Impl void getPointerPosition(vpImagePoint &ip, unsigned int scale) { gint u, v; - gdk_window_get_pointer(m_widget->window, &u, &v, NULL); + gdk_window_get_pointer(m_widget->window, &u, &v, nullptr); ip.set_u(static_cast(u) * scale); ip.set_v(static_cast(v) * scale); } @@ -520,7 +520,7 @@ class vpDisplayGTK::Impl void getScreenSize(bool is_init, unsigned int &w, unsigned int &h) { if (!is_init) { - int *argc = NULL; + int *argc = nullptr; char **argv; gtk_init(argc, &argv); diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index 56e28f2bac..21b7ab1daa 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -102,9 +102,9 @@ unsigned int vpDisplayOpenCV::m_nbWindows = 0; vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) : vpDisplay(), #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), @@ -142,9 +142,9 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const vpScaleType scaleType) : vpDisplay(), #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), @@ -176,9 +176,9 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), @@ -212,9 +212,9 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const std::string &title, vpScaleType scaleType) : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), @@ -250,9 +250,9 @@ int main() vpDisplayOpenCV::vpDisplayOpenCV(int x, int y, const std::string &title) : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), @@ -310,9 +310,9 @@ int main() vpDisplayOpenCV::vpDisplayOpenCV() : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), @@ -585,7 +585,7 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) int depth = 8; int channels = 3; CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != NULL) { + if (m_background != nullptr) { if (m_background->nChannels != channels || m_background->depth != depth || m_background->height != (int)m_height || m_background->width != (int)m_width) { if (m_background->nChannels != 0) @@ -682,7 +682,7 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI int depth = 8; int channels = 3; CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != NULL) { + if (m_background != nullptr) { if (m_background->nChannels != channels || m_background->depth != depth || m_background->height != (int)m_height || m_background->width != (int)m_width) { if (m_background->nChannels != 0) @@ -792,7 +792,7 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) int depth = 8; int channels = 3; CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != NULL) { + if (m_background != nullptr) { if (m_background->nChannels != channels || m_background->depth != depth || m_background->height != (int)m_height || m_background->width != (int)m_width) { if (m_background->nChannels != 0) @@ -886,7 +886,7 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi int depth = 8; int channels = 3; CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != NULL) { + if (m_background != nullptr) { if (m_background->nChannels != channels || m_background->depth != depth || m_background->height != (int)m_height || m_background->width != (int)m_width) { if (m_background->nChannels != 0) @@ -992,14 +992,14 @@ void vpDisplayOpenCV::displayImage(const unsigned char * /* I */) { vpTRACE(" no */ void vpDisplayOpenCV::closeDisplay() { - if (col != NULL) { + if (col != nullptr) { delete[] col; - col = NULL; + col = nullptr; } #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - if (font != NULL) { + if (font != nullptr) { delete font; - font = NULL; + font = nullptr; } #endif if (m_displayHasBeenInitialized) { diff --git a/modules/gui/src/display/vpDisplayX.cpp b/modules/gui/src/display/vpDisplayX.cpp index b37a26af84..17892fd412 100644 --- a/modules/gui/src/display/vpDisplayX.cpp +++ b/modules/gui/src/display/vpDisplayX.cpp @@ -75,7 +75,7 @@ class vpDisplayX::Impl { public: Impl() - : display(NULL), window(), Ximage(NULL), lut(), context(), screen(0), event(), pixmap(), x_color(NULL), + : display(nullptr), window(), Ximage(nullptr), lut(), context(), screen(0), event(), pixmap(), x_color(nullptr), screen_depth(8), xcolor(), values(), ximage_data_init(false), RMask(0), GMask(0), BMask(0), RShift(0), GShift(0), BShift(0) { @@ -108,7 +108,7 @@ class vpDisplayX::Impl if (ximage_data_init == true) free(Ximage->data); - Ximage->data = NULL; + Ximage->data = nullptr; XDestroyImage(Ximage); XFreePixmap(display, pixmap); @@ -117,9 +117,9 @@ class vpDisplayX::Impl XDestroyWindow(display, window); XCloseDisplay(display); - if (x_color != NULL) { + if (x_color != nullptr) { delete[] x_color; - x_color = NULL; + x_color = nullptr; } } @@ -363,7 +363,7 @@ class vpDisplayX::Impl /* * 32-bit source, 24/32-bit destination */ - unsigned char *dst_32 = NULL; + unsigned char *dst_32 = nullptr; dst_32 = (unsigned char *)Ximage->data; if (scale == 1) { vpRGBa *bitmap = I.bitmap; @@ -952,7 +952,7 @@ class vpDisplayX::Impl I.resize(height, width); - unsigned char *src_32 = NULL; + unsigned char *src_32 = nullptr; src_32 = (unsigned char *)xi->data; if (screen_depth == 16) { @@ -1101,9 +1101,9 @@ class vpDisplayX::Impl int screen_; unsigned int depth; - if ((display_ = XOpenDisplay(NULL)) == NULL) { + if ((display_ = XOpenDisplay(nullptr)) == nullptr) { throw(vpDisplayException(vpDisplayException::connexionError, "Can't connect display on server %s.", - XDisplayName(NULL))); + XDisplayName(nullptr))); } screen_ = DefaultScreen(display_); depth = (unsigned int)DefaultDepth(display_, screen_); @@ -1118,9 +1118,9 @@ class vpDisplayX::Impl Display *display_; int screen_; - if ((display_ = XOpenDisplay(NULL)) == NULL) { + if ((display_ = XOpenDisplay(nullptr)) == nullptr) { throw(vpDisplayException(vpDisplayException::connexionError, "Can't connect display on server %s.", - XDisplayName(NULL))); + XDisplayName(nullptr))); } screen_ = DefaultScreen(display_); w = (unsigned int)DisplayWidth(display_, screen_); @@ -1131,7 +1131,7 @@ class vpDisplayX::Impl void init(unsigned int win_width, unsigned int win_height, int win_x, int win_y, const std::string &win_title) { - if (x_color == NULL) { + if (x_color == nullptr) { // id_unknown = number of predefined colors x_color = new unsigned long[vpColor::id_unknown]; } @@ -1147,8 +1147,8 @@ class vpDisplayX::Impl hints.y = win_y; } - if ((display = XOpenDisplay(NULL)) == NULL) { - vpERROR_TRACE("Can't connect display on server %s.\n", XDisplayName(NULL)); + if ((display = XOpenDisplay(nullptr)) == nullptr) { + vpERROR_TRACE("Can't connect display on server %s.\n", XDisplayName(nullptr)); throw(vpDisplayException(vpDisplayException::connexionError, "Can't connect display on server.")); } @@ -1533,7 +1533,7 @@ class vpDisplayX::Impl values.background = BlackPixel(display, screen); context = XCreateGC(display, window, GCPlaneMask | GCFillStyle | GCForeground | GCBackground, &values); - if (context == NULL) { + if (context == nullptr) { vpERROR_TRACE("Can't create graphics context."); throw(vpDisplayException(vpDisplayException::XWindowsError, "Can't create graphics context")); } @@ -1547,7 +1547,7 @@ class vpDisplayX::Impl // while ( event.xany.type != Expose ); { - Ximage = XCreateImage(display, DefaultVisual(display, screen), screen_depth, ZPixmap, 0, NULL, win_width, + Ximage = XCreateImage(display, DefaultVisual(display, screen), screen_depth, ZPixmap, 0, nullptr, win_width, win_height, XBitmapPad(display), 0); Ximage->data = (char *)malloc(win_height * (unsigned int)Ximage->bytes_per_line); diff --git a/modules/gui/src/display/windows/vpD3DRenderer.cpp b/modules/gui/src/display/windows/vpD3DRenderer.cpp index 0627a086cb..fe8357fe23 100644 --- a/modules/gui/src/display/windows/vpD3DRenderer.cpp +++ b/modules/gui/src/display/windows/vpD3DRenderer.cpp @@ -73,11 +73,11 @@ */ vpD3DRenderer::vpD3DRenderer() { - pD3D = NULL; - pd3dDevice = NULL; - pSprite = NULL; - pd3dText = NULL; - pd3dVideoText = NULL; + pD3D = nullptr; + pd3dDevice = nullptr; + pSprite = nullptr; + pd3dText = nullptr; + pd3dVideoText = nullptr; textWidth = 0; // D3D palette @@ -159,7 +159,7 @@ vpD3DRenderer::vpD3DRenderer() // Creates a logical font hFont = CreateFont(18, 0, 0, 0, FW_NORMAL, false, false, false, DEFAULT_CHARSET, OUT_DEFAULT_PRECIS, - CLIP_DEFAULT_PRECIS, DEFAULT_QUALITY, DEFAULT_PITCH | FF_DONTCARE, NULL); + CLIP_DEFAULT_PRECIS, DEFAULT_QUALITY, DEFAULT_PITCH | FF_DONTCARE, nullptr); } /*! @@ -170,13 +170,13 @@ vpD3DRenderer::~vpD3DRenderer() { DeleteObject(hFont); - if (pd3dDevice != NULL) + if (pd3dDevice != nullptr) pd3dDevice->Release(); - if (pD3D != NULL) + if (pD3D != nullptr) pD3D->Release(); - if (pd3dText != NULL) + if (pd3dText != nullptr) pd3dText->Release(); - if (pd3dVideoText != NULL) + if (pd3dVideoText != nullptr) pd3dVideoText->Release(); } @@ -210,7 +210,7 @@ bool vpD3DRenderer::init(HWND hwnd, unsigned int width, unsigned int height) hWnd = hwnd; // D3D initialize - if (NULL == (pD3D = Direct3DCreate9(D3D_SDK_VERSION))) + if (nullptr == (pD3D = Direct3DCreate9(D3D_SDK_VERSION))) throw vpDisplayException(vpDisplayException::notInitializedError, "Can't initialize D3D!"); D3DDISPLAYMODE d3ddm; @@ -443,7 +443,7 @@ void vpD3DRenderer::convertROI(const vpImage &I, unsigned char *imBuffer void vpD3DRenderer::setImg(const vpImage &im) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; RECT r; @@ -479,7 +479,7 @@ void vpD3DRenderer::setImgROI(const vpImage &im, const vpImagePoint &iP, unsigned int height) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; int i_min = (std::max)((int)ceil(iP.get_i() / m_rscale), 0); @@ -519,7 +519,7 @@ void vpD3DRenderer::setImgROI(const vpImage &im, const vpImagePoint &iP, void vpD3DRenderer::setImg(const vpImage &im) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; RECT r; @@ -555,7 +555,7 @@ void vpD3DRenderer::setImgROI(const vpImage &im, const vpImagePoi unsigned int height) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; int i_min = (std::max)((int)ceil(iP.get_i() / m_rscale), 0); @@ -596,7 +596,7 @@ void vpD3DRenderer::setImgROI(const vpImage &im, const vpImagePoi bool vpD3DRenderer::render() { // Clears the back buffer to a blue color - // pd3dDevice->Clear( 0, NULL, D3DCLEAR_TARGET, + // pd3dDevice->Clear( 0, nullptr, D3DCLEAR_TARGET, // D3DCOLOR_XRGB(0,0,255), 1.0f, 0 ); // Begins the scene. @@ -617,17 +617,17 @@ bool vpD3DRenderer::render() #if (D3DX_SDK_VERSION <= 9) pSprite->Begin(); // - pSprite->Draw(pd3dVideoText, &r, NULL, NULL, NULL, NULL, 0xFFFFFFFF); + pSprite->Draw(pd3dVideoText, &r, nullptr, nullptr, nullptr, nullptr, 0xFFFFFFFF); #else pSprite->Begin(0); - pSprite->Draw(pd3dVideoText, &r, NULL, NULL, 0xFFFFFFFF); + pSprite->Draw(pd3dVideoText, &r, nullptr, nullptr, 0xFFFFFFFF); #endif pSprite->End(); // Ends the scene. pd3dDevice->EndScene(); // Presents the backbuffer - pd3dDevice->Present(NULL, NULL, NULL, NULL); + pd3dDevice->Present(nullptr, nullptr, nullptr, nullptr); return true; } @@ -647,7 +647,7 @@ void vpD3DRenderer::setPixel(const vpImagePoint &iP, const vpColor &color) } // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; RECT r; @@ -687,7 +687,7 @@ void vpD3DRenderer::drawLine(const vpImagePoint &ip1, const vpImagePoint &ip2, c unsigned int thickness, int style) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { // Will contain the texture's surface drawing context HDC hDCMem; @@ -742,7 +742,7 @@ void vpD3DRenderer::drawLine(const vpImagePoint &ip1, const vpImagePoint &ip2, c double j = ip1_.get_j(); // Move to the starting point - MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), nullptr); // Draw the line LineTo(hDCMem, vpMath::round(j / m_rscale), vpMath::round((i + deltai) / m_rscale)); } @@ -750,14 +750,14 @@ void vpD3DRenderer::drawLine(const vpImagePoint &ip1, const vpImagePoint &ip2, c for (unsigned int j = (unsigned int)ip1_.get_j(); j < ip2_.get_j(); j += (unsigned int)(2 * deltaj)) { double i = slope * j + orig; // Move to the starting point - MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), nullptr); // Draw the line LineTo(hDCMem, vpMath::round((j + deltaj) / m_rscale), vpMath::round((i + deltai) / m_rscale)); } } } else { // move to the starting point - MoveToEx(hDCMem, vpMath::round(ip1.get_u() / m_rscale), vpMath::round(ip1.get_v() / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(ip1.get_u() / m_rscale), vpMath::round(ip1.get_v() / m_rscale), nullptr); // Draw the line LineTo(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale)); } @@ -784,7 +784,7 @@ void vpD3DRenderer::drawRect(const vpImagePoint &topLeft, unsigned int width, un bool fill, unsigned int thickness) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { if (fill == false) { drawLine(topLeft, topLeft + vpImagePoint(0, width), color, thickness); drawLine(topLeft + vpImagePoint(0, width), topLeft + vpImagePoint(height, width), color, thickness); @@ -846,7 +846,7 @@ void vpD3DRenderer::drawRect(const vpImagePoint &topLeft, unsigned int width, un void vpD3DRenderer::clear(const vpColor &color) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; RECT r; @@ -928,7 +928,7 @@ void vpD3DRenderer::drawCircle(const vpImagePoint ¢er, unsigned int radius, return; // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { D3DLOCKED_RECT d3dLRect; RECT rec; @@ -1146,7 +1146,7 @@ void TextureToRGBa(vpImage &I, unsigned char *imBuffer, unsigned int pit void vpD3DRenderer::getImage(vpImage &I) { // if the device has been initialized - if (pd3dDevice != NULL) { + if (pd3dDevice != nullptr) { // resize the destination image as needed I.resize(m_rheight, m_rwidth); diff --git a/modules/gui/src/display/windows/vpDisplayWin32.cpp b/modules/gui/src/display/windows/vpDisplayWin32.cpp index 1f74bab7a1..dc0ffd0e4c 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -147,10 +147,10 @@ void vpDisplayWin32::init(unsigned int width, unsigned int height, int x, int y, param->title = this->m_title; // creates the window in a separate thread - hThread = CreateThread(NULL, 0, (LPTHREAD_START_ROUTINE)vpCreateWindow, param, 0, &threadId); + hThread = CreateThread(nullptr, 0, (LPTHREAD_START_ROUTINE)vpCreateWindow, param, 0, &threadId); // the initialization worked - iStatus = (hThread != (HANDLE)NULL); + iStatus = (hThread != (HANDLE)nullptr); m_displayHasBeenInitialized = true; } diff --git a/modules/gui/src/display/windows/vpGDIRenderer.cpp b/modules/gui/src/display/windows/vpGDIRenderer.cpp index b985f795e7..120161351c 100644 --- a/modules/gui/src/display/windows/vpGDIRenderer.cpp +++ b/modules/gui/src/display/windows/vpGDIRenderer.cpp @@ -47,10 +47,10 @@ /*! Constructor. */ -vpGDIRenderer::vpGDIRenderer() : m_bmp(NULL), m_bmp_width(0), m_bmp_height(0), timelost(0) +vpGDIRenderer::vpGDIRenderer() : m_bmp(nullptr), m_bmp_width(0), m_bmp_height(0), timelost(0) { // if the screen depth is not 32bpp, throw an exception - int bpp = GetDeviceCaps(GetDC(NULL), BITSPIXEL); + int bpp = GetDeviceCaps(GetDC(nullptr), BITSPIXEL); if (bpp != 32) throw vpDisplayException(vpDisplayException::depthNotSupportedError, "vpGDIRenderer supports only 32bits depth: screen is %dbits depth!", bpp); @@ -130,7 +130,7 @@ bool vpGDIRenderer::init(HWND hWindow, unsigned int width, unsigned int height) // creates the font m_hFont = CreateFont(18, 0, 0, 0, FW_NORMAL, false, false, false, DEFAULT_CHARSET, OUT_DEFAULT_PRECIS, - CLIP_DEFAULT_PRECIS, DEFAULT_QUALITY, DEFAULT_PITCH | FF_DONTCARE, NULL); + CLIP_DEFAULT_PRECIS, DEFAULT_QUALITY, DEFAULT_PITCH | FF_DONTCARE, nullptr); return true; } @@ -421,12 +421,12 @@ bool vpGDIRenderer::updateBitmap(HBITMAP &hBmp, unsigned char *imBuffer, unsigne // just replace the content SetBitmapBits(hBmp, w * h * 4, imBuffer); } else { - if (hBmp != NULL) { + if (hBmp != nullptr) { // delete the old BITMAP DeleteObject(hBmp); } // create a new BITMAP from this buffer - if ((hBmp = CreateBitmap(static_cast(w), static_cast(h), 1, 32, (void *)imBuffer)) == NULL) + if ((hBmp = CreateBitmap(static_cast(w), static_cast(h), 1, 32, (void *)imBuffer)) == nullptr) return false; m_bmp_width = w; @@ -512,8 +512,8 @@ void vpGDIRenderer::setPixel(const vpImagePoint &iP, const vpColor &color) void vpGDIRenderer::drawLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness, int style) { - HDC hDCScreen = NULL, hDCMem = NULL; - HPEN hPen = NULL; + HDC hDCScreen = nullptr, hDCMem = nullptr; + HPEN hPen = nullptr; #ifdef GDI_ROBUST double start = vpTime::measureTimeMs(); while (vpTime::measureTimeMs() - start < 1000) { @@ -616,7 +616,7 @@ void vpGDIRenderer::drawLine(const vpImagePoint &ip1, const vpImagePoint &ip2, c double j = ip1_.get_j(); // Move to the starting point - MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), nullptr); // Draw the line LineTo(hDCMem, vpMath::round(j / m_rscale), vpMath::round((i + deltai) / m_rscale)); } @@ -624,14 +624,14 @@ void vpGDIRenderer::drawLine(const vpImagePoint &ip1, const vpImagePoint &ip2, c for (unsigned int j = (unsigned int)ip1_.get_j(); j < ip2_.get_j(); j += (unsigned int)(2 * deltaj)) { double i = slope * j + orig; // Move to the starting point - MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(j / m_rscale), vpMath::round(i / m_rscale), nullptr); // Draw the line LineTo(hDCMem, vpMath::round((j + deltaj) / m_rscale), vpMath::round((i + deltai) / m_rscale)); } } } else { // move to the starting point - MoveToEx(hDCMem, vpMath::round(ip1.get_u() / m_rscale), vpMath::round(ip1.get_v() / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(ip1.get_u() / m_rscale), vpMath::round(ip1.get_v() / m_rscale), nullptr); // Draw the line LineTo(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale)); } @@ -876,12 +876,12 @@ void vpGDIRenderer::drawCross(const vpImagePoint &ip, unsigned int size, const v SelectObject(hDCMem, hPen); // move to the starting point - MoveToEx(hDCMem, vpMath::round(ip.get_u() / m_rscale) - half_size, vpMath::round(ip.get_v() / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(ip.get_u() / m_rscale) - half_size, vpMath::round(ip.get_v() / m_rscale), nullptr); // Draw the first line (horizontal) LineTo(hDCMem, vpMath::round(ip.get_u() / m_rscale) + half_size, vpMath::round(ip.get_v() / m_rscale)); // move to the starting point - MoveToEx(hDCMem, vpMath::round(ip.get_u() / m_rscale), vpMath::round(ip.get_v() / m_rscale) - half_size, NULL); + MoveToEx(hDCMem, vpMath::round(ip.get_u() / m_rscale), vpMath::round(ip.get_v() / m_rscale) - half_size, nullptr); // Draw the second line (vertical) LineTo(hDCMem, vpMath::round(ip.get_u() / m_rscale), vpMath::round(ip.get_v() / m_rscale) + half_size); @@ -957,7 +957,7 @@ void vpGDIRenderer::drawArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, ip4.set_j(ip3.get_j() + a * h); if (lg > 2 * vpImagePoint::distance(ip2 / m_rscale, ip4)) { - MoveToEx(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale), nullptr); LineTo(hDCMem, vpMath::round(ip4.get_u()), vpMath::round(ip4.get_v())); } // t+=0.1 ; @@ -970,13 +970,13 @@ void vpGDIRenderer::drawArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, ip4.set_j(ip3.get_j() - a * h); if (lg > 2 * vpImagePoint::distance(ip2 / m_rscale, ip4)) { - MoveToEx(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale), nullptr); LineTo(hDCMem, vpMath::round(ip4.get_u()), vpMath::round(ip4.get_v())); } // t-=0.1 ; } - MoveToEx(hDCMem, vpMath::round(ip1.get_u() / m_rscale), vpMath::round(ip1.get_v() / m_rscale), NULL); + MoveToEx(hDCMem, vpMath::round(ip1.get_u() / m_rscale), vpMath::round(ip1.get_v() / m_rscale), nullptr); LineTo(hDCMem, vpMath::round(ip2.get_u() / m_rscale), vpMath::round(ip2.get_v() / m_rscale)); } diff --git a/modules/gui/src/display/windows/vpWin32API.cpp b/modules/gui/src/display/windows/vpWin32API.cpp index 285562c628..105853e7f4 100644 --- a/modules/gui/src/display/windows/vpWin32API.cpp +++ b/modules/gui/src/display/windows/vpWin32API.cpp @@ -47,8 +47,8 @@ DWORD vpProcessErrors(const std::string &api_name) LPVOID lpMsgBuf; DWORD err = GetLastError(); - FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, NULL, err, - MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPTSTR)&lpMsgBuf, 0, NULL); + FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, nullptr, err, + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPTSTR)&lpMsgBuf, 0, nullptr); std::cout << "call to " << api_name << " failed with the following error code: " << err << "(" << (LPTSTR)lpMsgBuf << ")" << std::endl; return err; @@ -91,12 +91,12 @@ void vpSelectObject(HWND hWnd, HDC hDC, HDC hDCMem, HGDIOBJ h) { HGDIOBJ ret = SelectObject(hDCMem, h); - if (ret == NULL) { + if (ret == nullptr) { vpProcessErrors("SelectObject"); double ms = vpTime::measureTimeMs(); - while (ret == NULL && vpTime::measureTimeMs() - ms < 5000) { + while (ret == nullptr && vpTime::measureTimeMs() - ms < 5000) { DeleteObject(h); DeleteDC(hDCMem); ReleaseDC(hWnd, hDC); @@ -129,7 +129,7 @@ COLORREF vpSetPixel(HDC hdc, int X, int Y, COLORREF crColor) HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, const VOID *lpvBits) { HBITMAP ret = CreateBitmap(nWidth, nHeight, cPlanes, cBitsPerPel, lpvBits); - if (ret == NULL) + if (ret == nullptr) vpProcessErrors("CreateBitmap"); return ret; diff --git a/modules/gui/src/display/windows/vpWin32Window.cpp b/modules/gui/src/display/windows/vpWin32Window.cpp index e09013ee77..3b2a0962b6 100644 --- a/modules/gui/src/display/windows/vpWin32Window.cpp +++ b/modules/gui/src/display/windows/vpWin32Window.cpp @@ -73,16 +73,16 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) { // the first time this callback is executed, put the window in initialized // state - if (window != NULL) { + if (window != nullptr) { if (!window->isInitialized()) { window->initialized = true; - vpReleaseSemaphore(window->semaInit, 1, NULL); + vpReleaseSemaphore(window->semaInit, 1, nullptr); } } switch (message) { case vpWM_DISPLAY: // redraw the whole window - InvalidateRect(window->getHWnd(), NULL, TRUE); + InvalidateRect(window->getHWnd(), nullptr, TRUE); UpdateWindow(window->getHWnd()); break; @@ -104,7 +104,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) window->clickY = GET_Y_LPARAM(lParam); window->clickButton = vpMouseButton::button1; - vpReleaseSemaphore(window->semaClick, 1, NULL); + vpReleaseSemaphore(window->semaClick, 1, nullptr); } break; case WM_MBUTTONDOWN: { @@ -112,7 +112,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) window->clickY = GET_Y_LPARAM(lParam); window->clickButton = vpMouseButton::button2; - vpReleaseSemaphore(window->semaClick, 1, NULL); + vpReleaseSemaphore(window->semaClick, 1, nullptr); } break; case WM_RBUTTONDOWN: { @@ -120,7 +120,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) window->clickY = GET_Y_LPARAM(lParam); window->clickButton = vpMouseButton::button3; - vpReleaseSemaphore(window->semaClick, 1, NULL); + vpReleaseSemaphore(window->semaClick, 1, nullptr); } break; case WM_LBUTTONUP: { @@ -128,7 +128,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) window->clickYUp = GET_Y_LPARAM(lParam); window->clickButtonUp = vpMouseButton::button1; - vpReleaseSemaphore(window->semaClickUp, 1, NULL); + vpReleaseSemaphore(window->semaClickUp, 1, nullptr); } break; case WM_MBUTTONUP: { @@ -136,7 +136,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) window->clickYUp = GET_Y_LPARAM(lParam); window->clickButtonUp = vpMouseButton::button2; - vpReleaseSemaphore(window->semaClickUp, 1, NULL); + vpReleaseSemaphore(window->semaClickUp, 1, nullptr); } break; case WM_RBUTTONUP: { @@ -144,12 +144,12 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) window->clickYUp = GET_Y_LPARAM(lParam); window->clickButtonUp = vpMouseButton::button3; - vpReleaseSemaphore(window->semaClickUp, 1, NULL); + vpReleaseSemaphore(window->semaClickUp, 1, nullptr); } break; case WM_MOUSEMOVE: { window->coordX = GET_X_LPARAM(lParam); window->coordY = GET_Y_LPARAM(lParam); - vpReleaseSemaphore(window->semaMove, 1, NULL); + vpReleaseSemaphore(window->semaMove, 1, nullptr); } break; case WM_SYSKEYDOWN: @@ -160,7 +160,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) GetKeyNameText((LONG)lParam, window->lpString, 10); // 10 is the size of lpString // window->key = MapVirtualKey(wParam, MAPVK_VK_TO_CHAR); - vpReleaseSemaphore(window->semaKey, 1, NULL); + vpReleaseSemaphore(window->semaKey, 1, nullptr); break; } @@ -204,11 +204,11 @@ vpWin32Window::vpWin32Window(vpWin32Renderer *rend) : initialized(false) // this file (registered = false) // creates the semaphores - semaInit = CreateSemaphore(NULL, 0, 1, NULL); - semaClick = CreateSemaphore(NULL, 0, MAX_SEM_COUNT, NULL); - semaClickUp = CreateSemaphore(NULL, 0, MAX_SEM_COUNT, NULL); - semaKey = CreateSemaphore(NULL, 0, MAX_SEM_COUNT, NULL); - semaMove = CreateSemaphore(NULL, 0, MAX_SEM_COUNT, NULL); + semaInit = CreateSemaphore(nullptr, 0, 1, nullptr); + semaClick = CreateSemaphore(nullptr, 0, MAX_SEM_COUNT, nullptr); + semaClickUp = CreateSemaphore(nullptr, 0, MAX_SEM_COUNT, nullptr); + semaKey = CreateSemaphore(nullptr, 0, MAX_SEM_COUNT, nullptr); + semaMove = CreateSemaphore(nullptr, 0, MAX_SEM_COUNT, nullptr); } /*! @@ -256,12 +256,12 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i wcex.cbClsExtra = 0; wcex.cbWndExtra = 0; wcex.hInstance = hInst; - wcex.hIcon = LoadIcon(NULL, IDI_APPLICATION); - wcex.hCursor = LoadCursor(NULL, IDC_ARROW); + wcex.hIcon = LoadIcon(nullptr, IDI_APPLICATION); + wcex.hCursor = LoadCursor(nullptr, IDC_ARROW); wcex.hbrBackground = (HBRUSH)(COLOR_WINDOW + 1); - wcex.lpszMenuName = NULL; + wcex.lpszMenuName = nullptr; wcex.lpszClassName = g_szClassName; - wcex.hIconSm = LoadIcon(NULL, IDI_APPLICATION); + wcex.hIconSm = LoadIcon(nullptr, IDI_APPLICATION); RegisterClassEx(&wcex); @@ -271,13 +271,13 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i // creates the window hWnd = CreateWindowEx(WS_EX_APPWINDOW, g_szClassName, title, style, posx, posy, rect.right - rect.left, - rect.bottom - rect.top, NULL, NULL, hInst, NULL); - if (hWnd == NULL) { + rect.bottom - rect.top, nullptr, nullptr, hInst, nullptr); + if (hWnd == nullptr) { DWORD err = GetLastError(); std::cout << "err CreateWindowEx=" << err << std::endl; throw vpDisplayException(vpDisplayException::cannotOpenWindowError, "Can't create the window!"); } - SetWindowPos(hWnd, NULL, 0, 0, rect.right - rect.left, rect.bottom - rect.top, SWP_NOZORDER | SWP_NOMOVE); + SetWindowPos(hWnd, nullptr, 0, 0, rect.right - rect.left, rect.bottom - rect.top, SWP_NOZORDER | SWP_NOMOVE); // needed if we want to access it from the callback method (message handler) window = this; @@ -294,14 +294,14 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i // starts the message loop while (true) { - BOOL val = GetMessage(&msg, NULL, 0, 0); + BOOL val = GetMessage(&msg, nullptr, 0, 0); if (val == -1) { std::cout << "GetMessage error:" << GetLastError() << std::endl; break; } else if (val == 0) { break; } else { - if (!TranslateAccelerator(msg.hwnd, NULL, &msg)) { + if (!TranslateAccelerator(msg.hwnd, nullptr, &msg)) { TranslateMessage(&msg); DispatchMessage(&msg); } diff --git a/modules/gui/src/plot/vpPlot.cpp b/modules/gui/src/plot/vpPlot.cpp index fdfc1db1c4..f85f67f39d 100644 --- a/modules/gui/src/plot/vpPlot.cpp +++ b/modules/gui/src/plot/vpPlot.cpp @@ -55,7 +55,7 @@ Needs then a call to init(). */ -vpPlot::vpPlot() : I(), display(NULL), graphNbr(1), graphList(NULL), margei(30), margej(40), factori(1.f), factorj(1.) +vpPlot::vpPlot() : I(), display(nullptr), graphNbr(1), graphList(nullptr), margei(30), margej(40), factori(1.f), factorj(1.) { } /*! This constructor creates a new window where the curves @@ -75,7 +75,7 @@ vpPlot::vpPlot() : I(), display(NULL), graphNbr(1), graphList(NULL), margei(30), \param title : Window title. */ vpPlot::vpPlot(unsigned int graph_nbr, unsigned int height, unsigned int width, int x, int y, const std::string &title) - : I(), display(NULL), graphNbr(1), graphList(NULL), margei(30), margej(40), factori(1.f), factorj(1.) + : I(), display(nullptr), graphNbr(1), graphList(nullptr), margei(30), margej(40), factori(1.f), factorj(1.) { init(graph_nbr, height, width, x, y, title); } @@ -124,13 +124,13 @@ void vpPlot::init(unsigned int graph_nbr, unsigned int height, unsigned int widt */ vpPlot::~vpPlot() { - if (graphList != NULL) { + if (graphList != nullptr) { delete[] graphList; - graphList = NULL; + graphList = nullptr; } - if (display != NULL) { + if (display != nullptr) { delete display; - display = NULL; + display = nullptr; } } diff --git a/modules/gui/src/plot/vpPlotGraph.cpp b/modules/gui/src/plot/vpPlotGraph.cpp index 156394d62a..4d11ea617a 100644 --- a/modules/gui/src/plot/vpPlotGraph.cpp +++ b/modules/gui/src/plot/vpPlotGraph.cpp @@ -60,7 +60,7 @@ void getGrid3DPoint(double pente, vpImagePoint &iPunit, vpImagePoint &ip1, vpIma vpPlotGraph::vpPlotGraph() : xorg(0.), yorg(0.), zoomx(1.), zoomy(1.), xmax(10), ymax(10), xmin(0), ymin(-10), xdelt(1), ydelt(1), gridx(true), - gridy(true), gridColor(), curveNbr(1), curveList(NULL), scaleInitialized(false), firstPoint(true), nbDivisionx(10), + gridy(true), gridColor(), curveNbr(1), curveList(nullptr), scaleInitialized(false), firstPoint(true), nbDivisionx(10), nbDivisiony(10), topLeft(), width(0), height(0), graphZone(), dTopLeft(), dWidth(0), dHeight(0), dGraphZone(), dTopLeft3D(), dGraphZone3D(), cam(), cMo(), cMf(), w_xval(0), w_xsize(0), w_yval(0), w_ysize(0), w_zval(0), w_zsize(0), ptXorg(0), ptYorg(0), ptZorg(0), zoomx_3D(1.), zoomy_3D(1.), zoomz_3D(1.), nbDivisionz(10), zorg(1.), @@ -77,9 +77,9 @@ vpPlotGraph::vpPlotGraph() vpPlotGraph::~vpPlotGraph() { - if (curveList != NULL) { + if (curveList != nullptr) { delete[] curveList; - curveList = NULL; + curveList = nullptr; } } diff --git a/modules/gui/test/display-with-dataset/testClick.cpp b/modules/gui/test/display-with-dataset/testClick.cpp index 8b3fe714df..3d2602b086 100644 --- a/modules/gui/test/display-with-dataset/testClick.cpp +++ b/modules/gui/test/display-with-dataset/testClick.cpp @@ -197,7 +197,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, vpDisplayType & break; case 'h': - usage(argv[0], NULL, ipath, dtype); + usage(argv[0], nullptr, ipath, dtype); return false; break; case 'c': @@ -216,7 +216,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, vpDisplayType & if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, dtype); + usage(argv[0], nullptr, ipath, dtype); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -311,7 +311,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_dtype); + usage(argv[0], nullptr, ipath, opt_dtype); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -329,7 +329,7 @@ int main(int argc, const char **argv) vpImageIo::read(I, filename); // Create a display for the image - vpDisplay *display = NULL; + vpDisplay *display = nullptr; switch (opt_dtype) { case vpX11: diff --git a/modules/gui/test/display-with-dataset/testDisplayScaled.cpp b/modules/gui/test/display-with-dataset/testDisplayScaled.cpp index c3c111b975..2c7457371a 100644 --- a/modules/gui/test/display-with-dataset/testDisplayScaled.cpp +++ b/modules/gui/test/display-with-dataset/testDisplayScaled.cpp @@ -61,7 +61,7 @@ template bool test(const std::string &display, vpImage &I, // backup the input image vpImage Ibackup(I); - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (display == "GDI") { #ifdef VISP_HAVE_GDI d = new vpDisplayGDI; @@ -249,7 +249,7 @@ template bool test(const std::string &display, vpImage &I, vpDisplay::close(I); - if (d != NULL) + if (d != nullptr) delete d; if (success) diff --git a/modules/gui/test/display-with-dataset/testMouseEvent.cpp b/modules/gui/test/display-with-dataset/testMouseEvent.cpp index cd4432532c..0b208897b3 100644 --- a/modules/gui/test/display-with-dataset/testMouseEvent.cpp +++ b/modules/gui/test/display-with-dataset/testMouseEvent.cpp @@ -269,7 +269,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp wait = true; break; case 'h': - usage(argv[0], NULL, ipath, ppath, first, last, step, dtype); + usage(argv[0], nullptr, ipath, ppath, first, last, step, dtype); return false; break; @@ -282,7 +282,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, ppath, first, last, step, dtype); + usage(argv[0], nullptr, ipath, ppath, first, last, step, dtype); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -385,7 +385,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty() && opt_ppath.empty()) { - usage(argv[0], NULL, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_dtype); + usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_dtype); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -431,7 +431,7 @@ int main(int argc, const char **argv) return EXIT_FAILURE; } // Create a display for the image - vpDisplay *display = NULL; + vpDisplay *display = nullptr; switch (opt_dtype) { case vpX11: diff --git a/modules/gui/test/display-with-dataset/testVideoDevice.cpp b/modules/gui/test/display-with-dataset/testVideoDevice.cpp index f9057e0d44..d73a428e71 100644 --- a/modules/gui/test/display-with-dataset/testVideoDevice.cpp +++ b/modules/gui/test/display-with-dataset/testVideoDevice.cpp @@ -195,7 +195,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, vpDisplayType & break; case 'h': - usage(argv[0], NULL, ipath, dtype); + usage(argv[0], nullptr, ipath, dtype); return false; break; case 'c': @@ -214,7 +214,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, vpDisplayType & if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, dtype); + usage(argv[0], nullptr, ipath, dtype); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -309,7 +309,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_dtype); + usage(argv[0], nullptr, ipath, opt_dtype); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl @@ -334,7 +334,7 @@ int main(int argc, const char **argv) vpImageIo::read(Irgba, filename); // Create a display for the image - vpDisplay *display = NULL; + vpDisplay *display = nullptr; switch (opt_dtype) { case vpX11: diff --git a/modules/gui/test/display/testDisplayPolygonLines.cpp b/modules/gui/test/display/testDisplayPolygonLines.cpp index 760c82129b..6b1d96c849 100644 --- a/modules/gui/test/display/testDisplayPolygonLines.cpp +++ b/modules/gui/test/display/testDisplayPolygonLines.cpp @@ -121,7 +121,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -134,7 +134,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/gui/test/display/testDisplayRoi.cpp b/modules/gui/test/display/testDisplayRoi.cpp index 1917eb0858..78d780cf7a 100644 --- a/modules/gui/test/display/testDisplayRoi.cpp +++ b/modules/gui/test/display/testDisplayRoi.cpp @@ -125,7 +125,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -138,7 +138,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/gui/test/display/testDisplays.cpp b/modules/gui/test/display/testDisplays.cpp index 0d60c02122..fe5c88ec35 100644 --- a/modules/gui/test/display/testDisplays.cpp +++ b/modules/gui/test/display/testDisplays.cpp @@ -122,7 +122,7 @@ static bool getOptions(int argc, const char **argv, bool &list, bool &click_allo list = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; case 'c': @@ -141,7 +141,7 @@ static bool getOptions(int argc, const char **argv, bool &list, bool &click_allo if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/gui/test/display/testVideoDeviceDual.cpp b/modules/gui/test/display/testVideoDeviceDual.cpp index 7357097f70..ea2a4e710d 100644 --- a/modules/gui/test/display/testVideoDeviceDual.cpp +++ b/modules/gui/test/display/testVideoDeviceDual.cpp @@ -170,7 +170,7 @@ bool getOptions(int argc, const char **argv, vpDisplayType &dtype, bool &list, b break; case 'h': - usage(argv[0], NULL, dtype); + usage(argv[0], nullptr, dtype); return false; break; case 'c': @@ -189,7 +189,7 @@ bool getOptions(int argc, const char **argv, vpDisplayType &dtype, bool &list, b if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, dtype); + usage(argv[0], nullptr, dtype); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -261,7 +261,7 @@ int main(int argc, const char **argv) I2 = 255; // Create 2 display - vpDisplay *d1 = NULL, *d2 = NULL; + vpDisplay *d1 = nullptr, *d2 = nullptr; // Initialize the displays switch (opt_dtype) { diff --git a/modules/imgproc/include/visp3/imgproc/vpContours.h b/modules/imgproc/include/visp3/imgproc/vpContours.h index bc3265285a..9d2d79c858 100644 --- a/modules/imgproc/include/visp3/imgproc/vpContours.h +++ b/modules/imgproc/include/visp3/imgproc/vpContours.h @@ -218,18 +218,18 @@ struct vpContour /*! * Default constructor. */ - vpContour() : m_children(), m_contourType(vp::CONTOUR_HOLE), m_parent(NULL), m_points() { } + vpContour() : m_children(), m_contourType(vp::CONTOUR_HOLE), m_parent(nullptr), m_points() { } /*! * Constructor of a given contour type. */ - vpContour(const vpContourType &type) : m_children(), m_contourType(type), m_parent(NULL), m_points() { } + vpContour(const vpContourType &type) : m_children(), m_contourType(type), m_parent(nullptr), m_points() { } /*! * Copy constructor. */ vpContour(const vpContour &contour) - : m_children(), m_contourType(contour.m_contourType), m_parent(NULL), m_points(contour.m_points) + : m_children(), m_contourType(contour.m_contourType), m_parent(nullptr), m_points(contour.m_points) { // Copy the underlying contours @@ -247,10 +247,10 @@ struct vpContour virtual ~vpContour() { for (std::vector::iterator it = m_children.begin(); it != m_children.end(); ++it) { - (*it)->m_parent = NULL; - if (*it != NULL) { + (*it)->m_parent = nullptr; + if (*it != nullptr) { delete *it; - *it = NULL; + *it = nullptr; } } } @@ -262,20 +262,20 @@ struct vpContour { m_contourType = other.m_contourType; - if (m_parent == NULL) { + if (m_parent == nullptr) { // We are a root or an uninitialized contour so delete everything for (std::vector::iterator it = m_children.begin(); it != m_children.end(); ++it) { - (*it)->m_parent = NULL; - if (*it != NULL) { + (*it)->m_parent = nullptr; + if (*it != nullptr) { delete *it; - *it = NULL; + *it = nullptr; } } } else { // Make the current contour the root contour // to avoid problem when deleting - m_parent = NULL; + m_parent = nullptr; } m_children.clear(); @@ -295,7 +295,7 @@ struct vpContour { m_parent = parent; - if (parent != NULL) { + if (parent != nullptr) { parent->m_children.push_back(this); } } diff --git a/modules/imgproc/src/vpContours.cpp b/modules/imgproc/src/vpContours.cpp index 36b86af5fc..cefb7cdf92 100644 --- a/modules/imgproc/src/vpContours.cpp +++ b/modules/imgproc/src/vpContours.cpp @@ -322,7 +322,7 @@ void findContours(const vpImage &I_original, vpContour &contours, if (isOuter || isHole) { // else (1) (c) vpContour *border = new vpContour; - vpContour *borderPrime = NULL; + vpContour *borderPrime = nullptr; vpImagePoint from(i, j); if (isOuter) { @@ -399,13 +399,13 @@ void findContours(const vpImage &I_original, vpContour &contours, if (retrievalMode == CONTOUR_RETR_EXTERNAL || retrievalMode == CONTOUR_RETR_LIST) { // Delete contours content - contours.m_parent = NULL; + contours.m_parent = nullptr; for (std::vector::iterator it = contours.m_children.begin(); it != contours.m_children.end(); ++it) { - (*it)->m_parent = NULL; - if (*it != NULL) { + (*it)->m_parent = nullptr; + if (*it != nullptr) { delete *it; - *it = NULL; + *it = nullptr; } } @@ -444,6 +444,6 @@ void findContours(const vpImage &I_original, vpContour &contours, } delete root; - root = NULL; + root = nullptr; } }; diff --git a/modules/imgproc/test/with-dataset/testAutoThreshold.cpp b/modules/imgproc/test/with-dataset/testAutoThreshold.cpp index e25b9a2c8e..b4eca72f85 100644 --- a/modules/imgproc/test/with-dataset/testAutoThreshold.cpp +++ b/modules/imgproc/test/with-dataset/testAutoThreshold.cpp @@ -123,7 +123,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -140,7 +140,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -204,7 +204,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -225,7 +225,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/imgproc/test/with-dataset/testConnectedComponents.cpp b/modules/imgproc/test/with-dataset/testConnectedComponents.cpp index 64d5aca7f8..970002f264 100644 --- a/modules/imgproc/test/with-dataset/testConnectedComponents.cpp +++ b/modules/imgproc/test/with-dataset/testConnectedComponents.cpp @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -137,7 +137,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -243,7 +243,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -264,7 +264,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/imgproc/test/with-dataset/testContours.cpp b/modules/imgproc/test/with-dataset/testContours.cpp index e094dd7dc7..029e2d8ece 100644 --- a/modules/imgproc/test/with-dataset/testContours.cpp +++ b/modules/imgproc/test/with-dataset/testContours.cpp @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -137,7 +137,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -230,7 +230,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -251,7 +251,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/imgproc/test/with-dataset/testFloodFill.cpp b/modules/imgproc/test/with-dataset/testFloodFill.cpp index b6ecd2e7a1..e03293ac7a 100644 --- a/modules/imgproc/test/with-dataset/testFloodFill.cpp +++ b/modules/imgproc/test/with-dataset/testFloodFill.cpp @@ -119,7 +119,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -136,7 +136,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -222,7 +222,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -243,7 +243,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/imgproc/test/with-dataset/testImgproc.cpp b/modules/imgproc/test/with-dataset/testImgproc.cpp index 6307069edb..c6b6a8a27d 100644 --- a/modules/imgproc/test/with-dataset/testImgproc.cpp +++ b/modules/imgproc/test/with-dataset/testImgproc.cpp @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op opath = optarg_; break; case 'h': - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); return false; break; @@ -137,7 +137,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, ipath, opath, user); + usage(argv[0], nullptr, ipath, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -201,7 +201,7 @@ int main(int argc, const char **argv) // Create the dirname vpIoTools::makeDirectory(opath); } catch (...) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; std::cerr << " Check your -o " << opt_opath << " option " << std::endl; @@ -222,7 +222,7 @@ int main(int argc, const char **argv) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL, ipath, opt_opath, username); + usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/io/include/visp3/io/vpImageQueue.h b/modules/io/include/visp3/io/vpImageQueue.h index f7ea820a87..8a8f9e318c 100644 --- a/modules/io/include/visp3/io/vpImageQueue.h +++ b/modules/io/include/visp3/io/vpImageQueue.h @@ -155,7 +155,7 @@ template class vpImageQueue m_queue_image.push(I); - if (data != NULL) { + if (data != nullptr) { m_queue_data.push(*data); } @@ -164,7 +164,7 @@ template class vpImageQueue m_queue_image.pop(); } - if (data != NULL) { + if (data != nullptr) { while (m_queue_data.size() > m_maxQueueSize) { m_queue_data.pop(); } @@ -177,12 +177,12 @@ template class vpImageQueue * Record helper that display information in the windows associated to the image, pop current image and additional * data in the queue. * \param[in] I : Image to record. - * \param[in] data : Data to record. Set to NULL when no additional data have to be considered. + * \param[in] data : Data to record. Set to nullptr when no additional data have to be considered. * \param[in] trigger_recording : External trigger to start data saving. * \param[in] disable_left_click : Disable left click usage to trigger data saving. * \return true when the used asked to quit using a right click in the display window. */ - bool record(const vpImage &I, std::string *data = NULL, bool trigger_recording = false, + bool record(const vpImage &I, std::string *data = nullptr, bool trigger_recording = false, bool disable_left_click = false) { if (I.display) { diff --git a/modules/io/include/visp3/io/vpParseArgv.h b/modules/io/include/visp3/io/vpParseArgv.h index 60bf1dd872..aa83214d54 100644 --- a/modules/io/include/visp3/io/vpParseArgv.h +++ b/modules/io/include/visp3/io/vpParseArgv.h @@ -60,19 +60,19 @@ int main(int argc, const char ** argv) { {"-bool", vpParseArgv::ARGV_CONSTANT_BOOL, 0, (char *) &b_val, "Flag enabled."}, - {"-int", vpParseArgv::ARGV_INT, (char*) NULL, (char *) &i_val, + {"-int", vpParseArgv::ARGV_INT, (char*) nullptr, (char *) &i_val, "An integer value."}, - {"-long", vpParseArgv::ARGV_LONG, (char*) NULL, (char *) &l_val, + {"-long", vpParseArgv::ARGV_LONG, (char*) nullptr, (char *) &l_val, "An integer value."}, - {"-float", vpParseArgv::ARGV_FLOAT, (char*) NULL, (char *) &f_val, + {"-float", vpParseArgv::ARGV_FLOAT, (char*) nullptr, (char *) &f_val, "A float value."}, - {"-double", vpParseArgv::ARGV_DOUBLE, (char*) NULL, (char *) &d_val, + {"-double", vpParseArgv::ARGV_DOUBLE, (char*) nullptr, (char *) &d_val, "A double value."}, - {"-string", vpParseArgv::ARGV_STRING, (char*) NULL, (char *) &s_val, + {"-string", vpParseArgv::ARGV_STRING, (char*) nullptr, (char *) &s_val, "A string value."}, - {"-h", vpParseArgv::ARGV_HELP, (char*) NULL, (char *) NULL, + {"-h", vpParseArgv::ARGV_HELP, (char*) nullptr, (char *) nullptr, "Print the help."}, - {(char*) NULL, vpParseArgv::ARGV_END, (char*) NULL, (char*) NULL, (char*) NULL} } ; + {(char*) nullptr, vpParseArgv::ARGV_END, (char*) nullptr, (char*) nullptr, (char*) nullptr} } ; // Read the command line options if(vpParseArgv::parse(&argc, argv, argTable, diff --git a/modules/io/src/image/private/vpImageIoLibjpeg.cpp b/modules/io/src/image/private/vpImageIoLibjpeg.cpp index 7ebf46c94b..ecd4aa39e8 100644 --- a/modules/io/src/image/private/vpImageIoLibjpeg.cpp +++ b/modules/io/src/image/private/vpImageIoLibjpeg.cpp @@ -74,7 +74,7 @@ void writeJPEGLibjpeg(const vpImage &I, const std::string &filena file = fopen(filename.c_str(), "wb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create JPEG file \"%s\"", filename.c_str())); } @@ -133,7 +133,7 @@ void writeJPEGLibjpeg(const vpImage &I, const std::string &filename, int file = fopen(filename.c_str(), "wb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create JPEG file \"%s\"", filename.c_str())); } @@ -204,7 +204,7 @@ void readJPEGLibjpeg(vpImage &I, const std::string &filename) file = fopen(filename.c_str(), "rb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot read JPEG file \"%s\"", filename.c_str())); } @@ -284,7 +284,7 @@ void readJPEGLibjpeg(vpImage &I, const std::string &filename) file = fopen(filename.c_str(), "rb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot read JPEG file \"%s\"", filename.c_str())); } diff --git a/modules/io/src/image/private/vpImageIoLibpng.cpp b/modules/io/src/image/private/vpImageIoLibpng.cpp index aed697c5b5..e3a8c4fc02 100644 --- a/modules/io/src/image/private/vpImageIoLibpng.cpp +++ b/modules/io/src/image/private/vpImageIoLibpng.cpp @@ -67,12 +67,12 @@ void writePNGLibpng(const vpImage &I, const std::string &filename file = fopen(filename.c_str(), "wb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PNG file \"%s\"", filename.c_str())); } /* create a png info struct */ - png_structp png_ptr = png_create_write_struct(PNG_LIBPNG_VER_STRING, NULL, NULL, NULL); + png_structp png_ptr = png_create_write_struct(PNG_LIBPNG_VER_STRING, nullptr, nullptr, nullptr); if (!png_ptr) { fclose(file); vpERROR_TRACE("Error during png_create_write_struct()\n"); @@ -82,7 +82,7 @@ void writePNGLibpng(const vpImage &I, const std::string &filename png_infop info_ptr = png_create_info_struct(png_ptr); if (!info_ptr) { fclose(file); - png_destroy_write_struct(&png_ptr, NULL); + png_destroy_write_struct(&png_ptr, nullptr); vpERROR_TRACE("Error during png_create_info_struct()\n"); throw(vpImageException(vpImageException::ioError, "PNG write error")); } @@ -134,7 +134,7 @@ void writePNGLibpng(const vpImage &I, const std::string &filename png_write_image(png_ptr, row_ptrs); - png_write_end(png_ptr, NULL); + png_write_end(png_ptr, nullptr); for (unsigned int j = 0; j < height; j++) delete[] row_ptrs[j]; @@ -164,12 +164,12 @@ void writePNGLibpng(const vpImage &I, const std::string &filename) file = fopen(filename.c_str(), "wb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PNG file \"%s\"", filename.c_str())); } /* create a png info struct */ - png_structp png_ptr = png_create_write_struct(PNG_LIBPNG_VER_STRING, NULL, NULL, NULL); + png_structp png_ptr = png_create_write_struct(PNG_LIBPNG_VER_STRING, nullptr, nullptr, nullptr); if (!png_ptr) { fclose(file); vpERROR_TRACE("Error during png_create_write_struct()\n"); @@ -179,7 +179,7 @@ void writePNGLibpng(const vpImage &I, const std::string &filename) png_infop info_ptr = png_create_info_struct(png_ptr); if (!info_ptr) { fclose(file); - png_destroy_write_struct(&png_ptr, NULL); + png_destroy_write_struct(&png_ptr, nullptr); vpERROR_TRACE("Error during png_create_info_struct()\n"); throw(vpImageException(vpImageException::ioError, "PNG write error")); } @@ -236,7 +236,7 @@ void writePNGLibpng(const vpImage &I, const std::string &filename) png_write_image(png_ptr, row_ptrs); - png_write_end(png_ptr, NULL); + png_write_end(png_ptr, nullptr); for (unsigned int j = 0; j < height; j++) delete[] row_ptrs[j]; @@ -274,7 +274,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) file = fopen(filename.c_str(), "rb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot read file \"%s\"", filename.c_str())); } @@ -293,8 +293,8 @@ void readPNGLibpng(vpImage &I, const std::string &filename) /* create a png read struct */ // printf("version %s\n", PNG_LIBPNG_VER_STRING); - png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, NULL, NULL, NULL); - if (png_ptr == NULL) { + png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, nullptr, nullptr, nullptr); + if (png_ptr == nullptr) { fprintf(stderr, "error: can't create a png read structure!\n"); fclose(file); throw(vpImageException(vpImageException::ioError, "error reading png file")); @@ -302,10 +302,10 @@ void readPNGLibpng(vpImage &I, const std::string &filename) /* create a png info struct */ png_infop info_ptr = png_create_info_struct(png_ptr); - if (info_ptr == NULL) { + if (info_ptr == nullptr) { fprintf(stderr, "error: can't create a png info structure!\n"); fclose(file); - png_destroy_read_struct(&png_ptr, NULL, NULL); + png_destroy_read_struct(&png_ptr, nullptr, nullptr); throw(vpImageException(vpImageException::ioError, "error reading png file")); } @@ -313,7 +313,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) */ if (setjmp(png_jmpbuf(png_ptr))) { fclose(file); - png_destroy_read_struct(&png_ptr, &info_ptr, NULL); + png_destroy_read_struct(&png_ptr, &info_ptr, nullptr); vpERROR_TRACE("Error during init io\n"); throw(vpImageException(vpImageException::ioError, "PNG read error")); } @@ -417,8 +417,8 @@ void readPNGLibpng(vpImage &I, const std::string &filename) delete[](png_bytep) rowPtrs; delete[] data; - png_read_end(png_ptr, NULL); - png_destroy_read_struct(&png_ptr, &info_ptr, NULL); + png_read_end(png_ptr, nullptr); + png_destroy_read_struct(&png_ptr, &info_ptr, nullptr); fclose(file); } @@ -452,7 +452,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) file = fopen(filename.c_str(), "rb"); - if (file == NULL) { + if (file == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot read file \"%s\"", filename.c_str())); } @@ -470,7 +470,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) } /* create a png read struct */ - png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, NULL, NULL, NULL); + png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, nullptr, nullptr, nullptr); if (!png_ptr) { fclose(file); vpERROR_TRACE("Error during png_create_read_struct()\n"); @@ -481,7 +481,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) png_infop info_ptr = png_create_info_struct(png_ptr); if (!info_ptr) { fclose(file); - png_destroy_read_struct(&png_ptr, NULL, NULL); + png_destroy_read_struct(&png_ptr, nullptr, nullptr); vpERROR_TRACE("Error during png_create_info_struct()\n"); throw(vpImageException(vpImageException::ioError, "PNG read error")); } @@ -490,7 +490,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) */ if (setjmp(png_jmpbuf(png_ptr))) { fclose(file); - png_destroy_read_struct(&png_ptr, &info_ptr, NULL); + png_destroy_read_struct(&png_ptr, &info_ptr, nullptr); vpERROR_TRACE("Error during init io\n"); throw(vpImageException(vpImageException::ioError, "PNG read error")); } @@ -594,8 +594,8 @@ void readPNGLibpng(vpImage &I, const std::string &filename) delete[](png_bytep) rowPtrs; delete[] data; - png_read_end(png_ptr, NULL); - png_destroy_read_struct(&png_ptr, &info_ptr, NULL); + png_read_end(png_ptr, nullptr); + png_destroy_read_struct(&png_ptr, &info_ptr, nullptr); fclose(file); } #endif diff --git a/modules/io/src/image/private/vpImageIoPortable.cpp b/modules/io/src/image/private/vpImageIoPortable.cpp index 489bd1a449..7960632c44 100644 --- a/modules/io/src/image/private/vpImageIoPortable.cpp +++ b/modules/io/src/image/private/vpImageIoPortable.cpp @@ -190,7 +190,7 @@ void vp_writePFM(const vpImage &I, const std::string &filename) fd = fopen(filename.c_str(), "wb"); - if (fd == NULL) { + if (fd == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PFM file \"%s\"", filename.c_str())); } @@ -222,7 +222,7 @@ void vp_writePFM_HDR(const vpImage &I, const std::string &filename) } FILE *fd = fopen(filename.c_str(), "wb"); - if (fd == NULL) { + if (fd == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PFM file \"%s\"", filename.c_str())); } @@ -258,7 +258,7 @@ void vp_writePFM_HDR(const vpImage &I, const std::string &filename) } FILE *fd = fopen(filename.c_str(), "wb"); - if (fd == NULL) { + if (fd == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PFM file \"%s\"", filename.c_str())); } @@ -308,7 +308,7 @@ void vp_writePGM(const vpImage &I, const std::string &filename) fd = fopen(filename.c_str(), "wb"); - if (fd == NULL) { + if (fd == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PGM file \"%s\"", filename.c_str())); } @@ -373,7 +373,7 @@ void vp_writePGM(const vpImage &I, const std::string &filename) fd = fopen(filename.c_str(), "wb"); - if (fd == NULL) { + if (fd == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PGM file \"%s\"", filename.c_str())); } @@ -806,7 +806,7 @@ void vp_writePPM(const vpImage &I, const std::string &filename) f = fopen(filename.c_str(), "wb"); - if (f == NULL) { + if (f == nullptr) { throw(vpImageException(vpImageException::ioError, "Cannot create PPM file \"%s\"", filename.c_str())); } diff --git a/modules/io/src/image/private/vpImageIoStb.cpp b/modules/io/src/image/private/vpImageIoStb.cpp index 3db5e29804..40d52ba5e8 100644 --- a/modules/io/src/image/private/vpImageIoStb.cpp +++ b/modules/io/src/image/private/vpImageIoStb.cpp @@ -56,7 +56,7 @@ void readStb(vpImage &I, const std::string &filename) { int width = 0, height = 0, channels = 0; unsigned char *image = stbi_load(filename.c_str(), &width, &height, &channels, STBI_grey); - if (image == NULL) { + if (image == nullptr) { throw(vpImageException(vpImageException::ioError, "Can't read the image: %s", filename.c_str())); } I.init(image, static_cast(height), static_cast(width), true); @@ -67,7 +67,7 @@ void readStb(vpImage &I, const std::string &filename) { int width = 0, height = 0, channels = 0; unsigned char *image = stbi_load(filename.c_str(), &width, &height, &channels, STBI_rgb_alpha); - if (image == NULL) { + if (image == nullptr) { throw(vpImageException(vpImageException::ioError, "Can't read the image: %s", filename.c_str())); } I.init(reinterpret_cast(image), static_cast(height), static_cast(width), true); diff --git a/modules/io/src/image/private/vpImageIoTinyEXR.cpp b/modules/io/src/image/private/vpImageIoTinyEXR.cpp index 780c903ca5..be16de13f3 100644 --- a/modules/io/src/image/private/vpImageIoTinyEXR.cpp +++ b/modules/io/src/image/private/vpImageIoTinyEXR.cpp @@ -63,7 +63,7 @@ void readEXRTiny(vpImage &I, const std::string &filename) EXRHeader exr_header; InitEXRHeader(&exr_header); - const char *err = NULL; // or `nullptr` in C++11 or later. + const char *err = nullptr; // or `nullptr` in C++11 or later. ret = ParseEXRHeaderFromFile(&exr_header, &exr_version, filename.c_str(), &err); if (ret != 0) { std::string err_msg(err); @@ -136,7 +136,7 @@ void readEXRTiny(vpImage &I, const std::string &filename) EXRHeader exr_header; InitEXRHeader(&exr_header); - const char *err = NULL; // or `nullptr` in C++11 or later. + const char *err = nullptr; // or `nullptr` in C++11 or later. ret = ParseEXRHeaderFromFile(&exr_header, &exr_version, filename.c_str(), &err); if (ret != 0) { std::string err_msg(err); @@ -236,7 +236,7 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) header.requested_pixel_types[i] = TINYEXR_PIXELTYPE_FLOAT; // pixel type of output image to be stored in .EXR } - const char *err = NULL; // or nullptr in C++11 or later. + const char *err = nullptr; // or nullptr in C++11 or later. int ret = SaveEXRImageToFile(&image, &header, filename.c_str(), &err); if (ret != TINYEXR_SUCCESS) { std::string err_msg(err); @@ -298,7 +298,7 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) header.requested_pixel_types[i] = TINYEXR_PIXELTYPE_FLOAT; // pixel type of output image to be stored in .EXR } - const char *err = NULL; // or nullptr in C++11 or later. + const char *err = nullptr; // or nullptr in C++11 or later. int ret = SaveEXRImageToFile(&image, &header, filename.c_str(), &err); if (ret != TINYEXR_SUCCESS) { std::string err_msg(err); diff --git a/modules/io/src/tools/vpKeyboard.cpp b/modules/io/src/tools/vpKeyboard.cpp index 6f4a2f5f0a..76c202b0c8 100644 --- a/modules/io/src/tools/vpKeyboard.cpp +++ b/modules/io/src/tools/vpKeyboard.cpp @@ -102,7 +102,7 @@ int vpKeyboard::kbhit() FD_ZERO(&readfds); FD_SET(STDIN_FILENO, &readfds); - return select(STDIN_FILENO + 1, &readfds, NULL, NULL, &tv) == 1; + return select(STDIN_FILENO + 1, &readfds, nullptr, nullptr, &tv) == 1; #elif defined(_WIN32) && !defined(WINRT) return _kbhit(); #elif defined(_WIN32) && defined(WINRT) diff --git a/modules/io/src/tools/vpParseArgv.cpp b/modules/io/src/tools/vpParseArgv.cpp index c15efc7b00..856646a0b3 100644 --- a/modules/io/src/tools/vpParseArgv.cpp +++ b/modules/io/src/tools/vpParseArgv.cpp @@ -38,8 +38,8 @@ */ vpParseArgv::vpArgvInfo vpParseArgv::defaultTable[2] = { - {"-help", ARGV_HELP, (char *)NULL, (char *)NULL, "Print summary of command-line options and abort.\n"}, - {NULL, ARGV_END, (char *)NULL, (char *)NULL, (char *)NULL}}; + {"-help", ARGV_HELP, (char *)nullptr, (char *)nullptr, "Print summary of command-line options and abort.\n"}, + {nullptr, ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; int (*handlerProc1)(const char *dst, const char *key, const char *argument); int (*handlerProc2)(const char *dst, const char *key, int valargc, const char **argument); @@ -112,7 +112,7 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i * matchPtr. */ - matchPtr = NULL; + matchPtr = nullptr; for (unsigned int i = 0; i < 2; i++) { if (i == 0) { infoPtr = argTable; @@ -120,7 +120,7 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i infoPtr = defaultTable; } for (; infoPtr->type != ARGV_END; infoPtr++) { - if (infoPtr->key == NULL) { + if (infoPtr->key == nullptr) { continue; } if ((infoPtr->key[1] != c) || (strncmp(infoPtr->key, curArg, length) != 0)) { @@ -133,14 +133,14 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i if (flags & ARGV_NO_ABBREV) { continue; } - if (matchPtr != NULL) { + if (matchPtr != nullptr) { FPRINTF(stderr, "ambiguous option \"%s\"\n", curArg); return true; } matchPtr = infoPtr; } } - if (matchPtr == NULL) { + if (matchPtr == nullptr) { /* * Unrecognized argument. Just copy it down, unless the caller @@ -176,7 +176,7 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i if (argc == 0) { goto missingArg; } else { - char *endPtr = NULL; + char *endPtr = nullptr; *(((int *)infoPtr->dst) + i) = (int)strtol(argv[srcIndex], &endPtr, 0); if ((endPtr == argv[srcIndex]) || (*endPtr != 0)) { @@ -196,7 +196,7 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i if (argc == 0) { goto missingArg; } else { - char *endPtr = NULL; + char *endPtr = nullptr; *(((long *)infoPtr->dst) + i) = strtol(argv[srcIndex], &endPtr, 0); if ((endPtr == argv[srcIndex]) || (*endPtr != 0)) { @@ -308,7 +308,7 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i dstIndex++; argc--; } - argv[dstIndex] = (char *)NULL; + argv[dstIndex] = (char *)nullptr; *argcPtr = dstIndex; return false; @@ -357,7 +357,7 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) for (unsigned int i = 0; i < 2; i++) { for (infoPtr = i ? defaultTable : argTable; infoPtr->type != ARGV_END; infoPtr++) { int length; - if (infoPtr->key == NULL) { + if (infoPtr->key == nullptr) { continue; } length = (int)strlen(infoPtr->key); @@ -370,7 +370,7 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) FPRINTF(stderr, "Command-specific options:"); for (unsigned int i = 0;; i++) { for (infoPtr = i ? defaultTable : argTable; infoPtr->type != ARGV_END; infoPtr++) { - if ((infoPtr->type == ARGV_HELP) && (infoPtr->key == NULL)) { + if ((infoPtr->type == ARGV_HELP) && (infoPtr->key == nullptr)) { FPRINTF(stderr, "\n%s", infoPtr->help); continue; } @@ -433,11 +433,11 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) if (nargs < 1) nargs = 1; string = *((const char **)infoPtr->dst); - if ((nargs == 1) && (string == NULL)) + if ((nargs == 1) && (string == nullptr)) break; for (unsigned long j = 0; j < nargs; j++) { string = *(((const char **)infoPtr->dst) + j); - if (string != NULL) { + if (string != nullptr) { FPRINTF(stderr, " \"%s\"", string); } } @@ -482,7 +482,7 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) \param param: Pointer to a pointer to a string for output. \return If valid option is found, the character value of that option is - returned, and *param points to the parameter if given, or is NULL if no + returned, and *param points to the parameter if given, or is nullptr if no param. \return If standalone parameter (with no option) is found, 1 is returned, @@ -492,15 +492,15 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) is returned, and *param points to the invalid argument. \return When end of argument list is reached, 0 is returned, and *param - is NULL. + is nullptr. */ int vpParseArgv::parse(int argc, const char **argv, const char *validOpts, const char **param) { static int iArg = 1; int chOpt; - const char *psz = NULL; - const char *pszParam = NULL; + const char *psz = nullptr; + const char *pszParam = nullptr; if (iArg < argc) { psz = &(argv[iArg][0]); @@ -510,7 +510,7 @@ int vpParseArgv::parse(int argc, const char **argv, const char *validOpts, const if (isalnum(chOpt) || ispunct(chOpt)) { // we have an option character psz = strchr(validOpts, chOpt); - if (psz != NULL) { + if (psz != nullptr) { // option is valid, we want to return chOpt if (psz[1] == ':') { // option can have a parameter diff --git a/modules/io/src/video/vpVideoReader.cpp b/modules/io/src/video/vpVideoReader.cpp index 134db3a30a..571a489490 100644 --- a/modules/io/src/video/vpVideoReader.cpp +++ b/modules/io/src/video/vpVideoReader.cpp @@ -49,7 +49,7 @@ Basic constructor. */ vpVideoReader::vpVideoReader() - : vpFrameGrabber(), m_imSequence(NULL), + : vpFrameGrabber(), m_imSequence(nullptr), #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) m_capture(), m_frame(), m_lastframe_unknown(false), #endif @@ -63,7 +63,7 @@ Basic destructor. */ vpVideoReader::~vpVideoReader() { - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { delete m_imSequence; } } @@ -247,7 +247,7 @@ void vpVideoReader::acquire(vpImage &I) if (!m_isOpen) { open(I); } - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { m_imSequence->setStep(m_frameStep); bool skip_frame = false; do { @@ -342,7 +342,7 @@ void vpVideoReader::acquire(vpImage &I) open(I); } - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { m_imSequence->setStep(m_frameStep); bool skip_frame = false; do { @@ -434,7 +434,7 @@ void vpVideoReader::acquire(vpImage &I) */ bool vpVideoReader::getFrame(vpImage &I, long frame_index) { - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { try { m_imSequence->acquire(I, frame_index); width = I.getWidth(); @@ -511,7 +511,7 @@ bool vpVideoReader::getFrame(vpImage &I, long frame_index) */ bool vpVideoReader::getFrame(vpImage &I, long frame_index) { - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { try { m_imSequence->acquire(I, frame_index); width = I.getWidth(); @@ -702,7 +702,7 @@ void vpVideoReader::findLastFrameIndex() throw(vpException(vpException::notInitialized, "file not yet opened")); } - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { if (!m_lastFrameIndexIsSet) { std::string imageNameFormat = vpIoTools::getName(m_videoName); std::string dirName = vpIoTools::getParent(m_videoName); @@ -754,7 +754,7 @@ void vpVideoReader::findLastFrameIndex() */ void vpVideoReader::findFirstFrameIndex() { - if (m_imSequence != NULL) { + if (m_imSequence != nullptr) { if (!m_firstFrameIndexIsSet) { std::string imageNameFormat = vpIoTools::getName(m_videoName); std::string dirName = vpIoTools::getParent(m_videoName); diff --git a/modules/java/generator/gen2.py b/modules/java/generator/gen2.py index 27928bc485..0b5fbc609b 100755 --- a/modules/java/generator/gen2.py +++ b/modules/java/generator/gen2.py @@ -12,17 +12,17 @@ ignored_arg_types = ["RNG*"] -gen_template_check_self = Template(""" $cname* _self_ = NULL; +gen_template_check_self = Template(""" $cname* _self_ = nullptr; if(PyObject_TypeCheck(self, &pyopencv_${name}_Type)) _self_ = ${amp}((pyopencv_${name}_t*)self)->v${get}; - if (_self_ == NULL) + if (_self_ == nullptr) return failmsgp("Incorrect type of self (must be '${name}' or its derivative)"); """) -gen_template_check_self_algo = Template(""" $cname* _self_ = NULL; +gen_template_check_self_algo = Template(""" $cname* _self_ = nullptr; if(PyObject_TypeCheck(self, &pyopencv_${name}_Type)) _self_ = dynamic_cast<$cname*>(${amp}((pyopencv_${name}_t*)self)->v.get()); - if (_self_ == NULL) + if (_self_ == nullptr) return failmsgp("Incorrect type of self (must be '${name}' or its derivative)"); """) @@ -35,7 +35,7 @@ gen_template_simple_call_constructor = Template("""new (&(self->v)) ${cname}${args}""") -gen_template_parse_args = Template("""const char* keywords[] = { $kw_list, NULL }; +gen_template_parse_args = Template("""const char* keywords[] = { $kw_list, nullptr }; if( PyArg_ParseTupleAndKeywords(args, kw, "$fmtspec", (char**)keywords, $parse_arglist)$code_cvt )""") gen_template_func_body = Template("""$code_decl @@ -77,7 +77,7 @@ template<> bool pyopencv_to(PyObject* src, ${cname}& dst, const char* name) { - if( src == NULL || src == Py_None ) + if( src == nullptr || src == Py_None ) return true; if(!PyObject_TypeCheck(src, &pyopencv_${name}_Type)) { @@ -120,7 +120,7 @@ template<> bool pyopencv_to(PyObject* src, Ptr<${cname}>& dst, const char* name) { - if( src == NULL || src == Py_None ) + if( src == nullptr || src == Py_None ) return true; if(!PyObject_TypeCheck(src, &pyopencv_${name}_Type)) { @@ -158,7 +158,7 @@ static PyGetSetDef pyopencv_${name}_getseters[] = {${getset_inits} - {NULL} /* Sentinel */ + {nullptr} /* Sentinel */ }; ${methods_code} @@ -166,7 +166,7 @@ static PyMethodDef pyopencv_${name}_methods[] = { ${methods_inits} - {NULL, NULL} + {nullptr, nullptr} }; static void pyopencv_${name}_specials(void) @@ -192,7 +192,7 @@ static PyObject* pyopencv_${name}_get_${member}(pyopencv_${name}_t* p, void *closure) { $cname* _self_ = dynamic_cast<$cname*>(p->v.get()); - if (_self_ == NULL) + if (_self_ == nullptr) return failmsgp("Incorrect type of object (must be '${name}' or its derivative)"); return pyopencv_from(_self_${access}${member}); } @@ -201,7 +201,7 @@ gen_template_set_prop = Template(""" static int pyopencv_${name}_set_${member}(pyopencv_${name}_t* p, PyObject *value, void *closure) { - if (value == NULL) + if (value == nullptr) { PyErr_SetString(PyExc_TypeError, "Cannot delete the ${member} attribute"); return -1; @@ -213,13 +213,13 @@ gen_template_set_prop_algo = Template(""" static int pyopencv_${name}_set_${member}(pyopencv_${name}_t* p, PyObject *value, void *closure) { - if (value == NULL) + if (value == nullptr) { PyErr_SetString(PyExc_TypeError, "Cannot delete the ${member} attribute"); return -1; } $cname* _self_ = dynamic_cast<$cname*>(p->v.get()); - if (_self_ == NULL) + if (_self_ == nullptr) { failmsgp("Incorrect type of object (must be '${name}' or its derivative)"); return -1; @@ -230,10 +230,10 @@ gen_template_prop_init = Template(""" - {(char*)"${member}", (getter)pyopencv_${name}_get_${member}, NULL, (char*)"${member}", NULL},""") + {(char*)"${member}", (getter)pyopencv_${name}_get_${member}, nullptr, (char*)"${member}", nullptr},""") gen_template_rw_prop_init = Template(""" - {(char*)"${member}", (getter)pyopencv_${name}_get_${member}, (setter)pyopencv_${name}_set_${member}, (char*)"${member}", NULL},""") + {(char*)"${member}", (getter)pyopencv_${name}_get_${member}, (setter)pyopencv_${name}_set_${member}, (char*)"${member}", nullptr},""") simple_argtype_mapping = { "bool": ("bool", "b", "0"), @@ -350,7 +350,7 @@ def gen_code(self, codegen): methods_code.write(m.gen_code(codegen)) methods_inits.write(m.get_tab_entry()) - baseptr = "NULL" + baseptr = "nullptr" if self.base and self.base in all_classes: baseptr = "&pyopencv_" + all_classes[self.base].name + "_Type" @@ -674,7 +674,7 @@ def gen_code(self, codegen): parse_name = a.name if a.py_inputarg: if amapping[1] == "O": - code_decl += " PyObject* pyobj_%s = NULL;\n" % (a.name,) + code_decl += " PyObject* pyobj_%s = nullptr;\n" % (a.name,) parse_name = "pyobj_" + a.name if a.tp == 'char': code_cvt_list.append("convert_to_char(pyobj_%s, &%s, %s)"% (a.name, a.name, a.crepr())) @@ -758,7 +758,7 @@ def gen_code(self, codegen): parse_arglist = ", ".join(["&" + all_cargs[argno][1] for aname, argno in v.py_arglist]), code_cvt = " &&\n ".join(code_cvt_list)) else: - code_parse = "if(PyObject_Size(args) == 0 && (kw == NULL || PyObject_Size(kw) == 0))" + code_parse = "if(PyObject_Size(args) == 0 && (kw == nullptr || PyObject_Size(kw) == 0))" if len(v.py_outlist) == 0: code_ret = "Py_RETURN_NONE" @@ -788,7 +788,7 @@ def gen_code(self, codegen): # try to execute each signature code += " PyErr_Clear();\n\n".join([" {\n" + v + " }\n" for v in all_code_variants]) - def_ret = "NULL" + def_ret = "nullptr" if self.isconstructor: def_ret = "-1" code += "\n return %s;\n}\n\n" % def_ret @@ -949,7 +949,7 @@ def gen_namespace(self, ns_name): if func.isconstructor: continue self.code_ns_reg.write(func.get_tab_entry()) - self.code_ns_reg.write(' {NULL, NULL}\n};\n\n') + self.code_ns_reg.write(' {nullptr, nullptr}\n};\n\n') self.code_ns_reg.write('static ConstDef consts_%s[] = {\n'%wname) for name, cname in sorted(ns.consts.items()): @@ -957,7 +957,7 @@ def gen_namespace(self, ns_name): compat_name = re.sub(r"([a-z])([A-Z])", r"\1_\2", name).upper() if name != compat_name: self.code_ns_reg.write(' {"%s", %s},\n'%(compat_name, cname)) - self.code_ns_reg.write(' {NULL, 0}\n};\n\n') + self.code_ns_reg.write(' {nullptr, 0}\n};\n\n') def gen_namespaces_reg(self): self.code_ns_reg.write('static void init_submodules(PyObject * root) \n{\n') diff --git a/modules/java/generator/gen_java.py b/modules/java/generator/gen_java.py index d7e980ac1f..d1df15517a 100755 --- a/modules/java/generator/gen_java.py +++ b/modules/java/generator/gen_java.py @@ -964,7 +964,7 @@ def gen_func(self, ci, fi, prop_name=''): else: cvname = ("me->" if not self.isSmartClass(ci) else "(*me)->") + name c_prologue.append( \ - "%(cls)s* me = (%(cls)s*) self; //TODO: check for NULL" \ + "%(cls)s* me = (%(cls)s*) self; //TODO: check for nullptr" \ % {"cls": reverseCamelCase(self.smartWrap(ci, fi.fullClass(isCPP=True)))} \ ) cvargs = [] @@ -1133,7 +1133,7 @@ def gen_class(self, ci): JNIEXPORT jstring JNICALL Java_org_visp_%(module)s_%(j_cls)s_toString (JNIEnv* env, jclass, jlong self) { - %(cls)s* me = (%(cls)s*) self; //TODO: check for NULL + %(cls)s* me = (%(cls)s*) self; //TODO: check for nullptr std::stringstream ss; ss << *me; return env->NewStringUTF(ss.str().c_str()); diff --git a/modules/java/generator/hdr_parser.py b/modules/java/generator/hdr_parser.py index 15a5e27bf3..2d93598481 100755 --- a/modules/java/generator/hdr_parser.py +++ b/modules/java/generator/hdr_parser.py @@ -533,7 +533,7 @@ def parse_func_decl(self, decl_str, docstring=""): eqpos = a.find("CV_WRAP_DEFAULT") if eqpos >= 0: defval, pos3 = self.get_macro_arg(a, eqpos) - if defval == "NULL": + if defval == "nullptr": defval = "0" if eqpos >= 0: a = a[:eqpos].strip() diff --git a/modules/java/generator/src/cpp/VpImageRGBa.cpp b/modules/java/generator/src/cpp/VpImageRGBa.cpp index b75fa1c9d9..4606e8387f 100644 --- a/modules/java/generator/src/cpp/VpImageRGBa.cpp +++ b/modules/java/generator/src/cpp/VpImageRGBa.cpp @@ -39,7 +39,7 @@ JNIEXPORT jlong JNICALL Java_org_visp_core_VpImageRGBa_n_1VpImageRGBa__IICCCC(JN JNIEXPORT jlong JNICALL Java_org_visp_core_VpImageRGBa_n_1VpImageRGBa___3BIIZ(JNIEnv *env, jclass, jbyteArray arr, jint h, jint w, jboolean copyData) { - jbyte *array = env->GetByteArrayElements(arr, NULL); + jbyte *array = env->GetByteArrayElements(arr, nullptr); return (jlong) new vpImage((vpRGBa *const)array, (const unsigned int)h, (const unsigned int)w, copyData); @@ -51,7 +51,7 @@ JNIEXPORT jlong JNICALL Java_org_visp_core_VpImageRGBa_n_1VpImageRGBa___3BIIZ(JN JNIEXPORT jint JNICALL Java_org_visp_core_VpImageRGBa_n_1cols(JNIEnv *env, jclass, jlong address) { (void)env; - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr return me->getCols(); } @@ -59,7 +59,7 @@ JNIEXPORT jint JNICALL Java_org_visp_core_VpImageRGBa_n_1cols(JNIEnv *env, jclas JNIEXPORT jint JNICALL Java_org_visp_core_VpImageRGBa_n_1rows(JNIEnv *env, jclass, jlong address) { (void)env; - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr return me->getRows(); } @@ -67,7 +67,7 @@ JNIEXPORT jint JNICALL Java_org_visp_core_VpImageRGBa_n_1rows(JNIEnv *env, jclas JNIEXPORT jbyteArray JNICALL Java_org_visp_core_VpImageRGBa_n_1getPixel(JNIEnv *env, jclass, jlong address, jint i, jint j) { - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr vpRGBa val = (*me)(i, j); jbyteArray ret = env->NewByteArray(4); unsigned char temp[] = {val.R, val.G, val.B, val.A}; @@ -78,7 +78,7 @@ JNIEXPORT jbyteArray JNICALL Java_org_visp_core_VpImageRGBa_n_1getPixel(JNIEnv * // Java Method: getPixels() JNIEXPORT jbyteArray JNICALL Java_org_visp_core_VpImageRGBa_n_1getPixels(JNIEnv *env, jclass, jlong address) { - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr jbyteArray ret = env->NewByteArray(me->getNumberOfPixel() * 4); env->SetByteArrayRegion(ret, 0, me->getNumberOfPixel() * 4, (jbyte *)me->bitmap); return ret; @@ -87,7 +87,7 @@ JNIEXPORT jbyteArray JNICALL Java_org_visp_core_VpImageRGBa_n_1getPixels(JNIEnv // Java Method: dump() JNIEXPORT jstring JNICALL Java_org_visp_core_VpImageRGBa_n_1dump(JNIEnv *env, jclass, jlong address) { - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr std::stringstream ss; ss << *me; return env->NewStringUTF(ss.str().c_str()); diff --git a/modules/java/generator/src/cpp/VpImageUChar.cpp b/modules/java/generator/src/cpp/VpImageUChar.cpp index e506ed48de..8de84ce7c9 100644 --- a/modules/java/generator/src/cpp/VpImageUChar.cpp +++ b/modules/java/generator/src/cpp/VpImageUChar.cpp @@ -38,7 +38,7 @@ JNIEXPORT jlong JNICALL Java_org_visp_core_VpImageUChar_n_1VpImageUChar__IIB(JNI JNIEXPORT jlong JNICALL Java_org_visp_core_VpImageUChar_n_1VpImageUChar___3BIIZ(JNIEnv *env, jclass, jbyteArray arr, jint h, jint w, jboolean copyData) { - jbyte *array = env->GetByteArrayElements(arr, NULL); + jbyte *array = env->GetByteArrayElements(arr, nullptr); return (jlong) new vpImage((u_char *const)array, (const unsigned int)h, (const unsigned int)w, copyData); @@ -50,7 +50,7 @@ JNIEXPORT jlong JNICALL Java_org_visp_core_VpImageUChar_n_1VpImageUChar___3BIIZ( JNIEXPORT jint JNICALL Java_org_visp_core_VpImageUChar_n_1cols(JNIEnv *env, jclass, jlong address) { (void)env; - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr return me->getCols(); } @@ -58,7 +58,7 @@ JNIEXPORT jint JNICALL Java_org_visp_core_VpImageUChar_n_1cols(JNIEnv *env, jcla JNIEXPORT jint JNICALL Java_org_visp_core_VpImageUChar_n_1rows(JNIEnv *env, jclass, jlong address) { (void)env; - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr return me->getRows(); } @@ -66,14 +66,14 @@ JNIEXPORT jint JNICALL Java_org_visp_core_VpImageUChar_n_1rows(JNIEnv *env, jcla JNIEXPORT jint JNICALL Java_org_visp_core_VpImageUChar_n_1getPixel(JNIEnv *env, jclass, jlong address, jint i, jint j) { (void)env; - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr return (*me)(i, j); } // Java Method: getPixels() JNIEXPORT jbyteArray JNICALL Java_org_visp_core_VpImageUChar_n_1getPixels(JNIEnv *env, jclass, jlong address) { - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr jbyteArray ret = env->NewByteArray(me->getNumberOfPixel()); env->SetByteArrayRegion(ret, 0, me->getNumberOfPixel(), (jbyte *)me->bitmap); return ret; @@ -82,7 +82,7 @@ JNIEXPORT jbyteArray JNICALL Java_org_visp_core_VpImageUChar_n_1getPixels(JNIEnv // Java Method: dump() JNIEXPORT jstring JNICALL Java_org_visp_core_VpImageUChar_n_1dump(JNIEnv *env, jclass, jlong address) { - vpImage *me = (vpImage *)address; // TODO: check for NULL + vpImage *me = (vpImage *)address; // TODO: check for nullptr std::stringstream ss; ss << *me; return env->NewStringUTF(ss.str().c_str()); diff --git a/modules/java/generator/src/cpp/listconverters.cpp b/modules/java/generator/src/cpp/listconverters.cpp index 478137eb1f..4259faecd5 100644 --- a/modules/java/generator/src/cpp/listconverters.cpp +++ b/modules/java/generator/src/cpp/listconverters.cpp @@ -103,11 +103,11 @@ std::vector List_to_vector_double(JNIEnv *env, jdoubleArray arr) jobjectArray vector_vector_vpImagePoint_to_List(JNIEnv *env, const std::vector > &V) { if (V.empty()) { - return NULL; + return nullptr; } size_t outerSize = V.size(); - jobjectArray outerArray = env->NewObjectArray(outerSize, env->FindClass("java/lang/Object"), NULL); + jobjectArray outerArray = env->NewObjectArray(outerSize, env->FindClass("java/lang/Object"), nullptr); for (int i = 0; i < env->GetArrayLength(outerArray); i++) { size_t innerSize = V[i].size(); @@ -128,11 +128,11 @@ jobjectArray vector_vector_vpImagePoint_to_List(JNIEnv *env, const std::vector > &V) { if (V.empty()) { - return NULL; + return nullptr; } size_t outerSize = V.size(); - jobjectArray outerArray = env->NewObjectArray(outerSize, env->FindClass("java/lang/Object"), NULL); + jobjectArray outerArray = env->NewObjectArray(outerSize, env->FindClass("java/lang/Object"), nullptr); for (int i = 0; i < env->GetArrayLength(outerArray); i++) { size_t innerSize = V[i].size(); @@ -166,17 +166,17 @@ map_string_vector_vector_double_to_array_native(JNIEnv *env, const std::map > > &map) { if (map.empty()) { - return NULL; + return nullptr; } size_t mapSize = map.size(); - jobjectArray mapArray = env->NewObjectArray(mapSize, env->FindClass("java/lang/Object"), NULL); + jobjectArray mapArray = env->NewObjectArray(mapSize, env->FindClass("java/lang/Object"), nullptr); int idx = 0; for (std::map > >::const_iterator it = map.begin(); it != map.end(); ++it, idx++) { size_t outerSize = it->second.size(); - jobjectArray outerArray = env->NewObjectArray(outerSize, env->FindClass("java/lang/Object"), NULL); + jobjectArray outerArray = env->NewObjectArray(outerSize, env->FindClass("java/lang/Object"), nullptr); for (int i = 0; i < env->GetArrayLength(outerArray); i++) { size_t innerSize = it->second[i].size(); @@ -200,7 +200,7 @@ map_string_vector_vector_double_to_array_native(JNIEnv *env, jobjectArray vector_string_to_array_native(JNIEnv *env, const std::vector &V) { if (V.empty()) { - return NULL; + return nullptr; } size_t vecSize = V.size(); diff --git a/modules/java/misc/core/gen_dict.json b/modules/java/misc/core/gen_dict.json index 1770423c94..f1d493a8f0 100644 --- a/modules/java/misc/core/gen_dict.json +++ b/modules/java/misc/core/gen_dict.json @@ -53,10 +53,10 @@ " static const char method_name[] = \"core::getKannalaBrandtDistortionCoefficients()\";", " try {", " LOGD(\"%s\", method_name);", - " vpCameraParameters *cam = (vpCameraParameters*) self; //TODO: check for NULL", + " vpCameraParameters *cam = (vpCameraParameters*) self; //TODO: check for nullptr", " std::vector coefs = cam->getKannalaBrandtDistortionCoefficients();", " jdoubleArray jCoefs = env->NewDoubleArray(coefs.size());", - " jdouble *ptr_jCoefs = NULL;", + " jdouble *ptr_jCoefs = nullptr;", " ptr_jCoefs = env->GetDoubleArrayElements(jCoefs, 0);", " for (size_t i = 0; i < coefs.size(); i++) {", " ptr_jCoefs[i] = coefs[i];", @@ -97,7 +97,7 @@ " static const char method_name[] = \"core::getWorldCoordinates_12()\";", " try {", " LOGD(\"%s\", method_name);", - " vpPoint* me = (vpPoint*) self; //TODO: check for NULL", + " vpPoint* me = (vpPoint*) self; //TODO: check for nullptr", " vpColVector _retval_ = me->getWorldCoordinates( );", " return (jlong) new vpColVector(_retval_);", " } catch(const std::exception &e) {", diff --git a/modules/java/misc/core/src/java/core+VpImageRGBa.java b/modules/java/misc/core/src/java/core+VpImageRGBa.java index 3f42aa9b83..a5b19a314b 100644 --- a/modules/java/misc/core/src/java/core+VpImageRGBa.java +++ b/modules/java/misc/core/src/java/core+VpImageRGBa.java @@ -8,7 +8,7 @@ public class VpImageRGBa { public VpImageRGBa(long addr){ if (addr == 0) - throw new java.lang.UnsupportedOperationException("Native object address is NULL"); + throw new java.lang.UnsupportedOperationException("Native object address is nullptr"); nativeObj = addr; } diff --git a/modules/java/misc/core/src/java/core+VpImageUChar.java b/modules/java/misc/core/src/java/core+VpImageUChar.java index e29d952537..581bcc10da 100644 --- a/modules/java/misc/core/src/java/core+VpImageUChar.java +++ b/modules/java/misc/core/src/java/core+VpImageUChar.java @@ -8,7 +8,7 @@ public class VpImageUChar { public VpImageUChar(long addr){ if (addr == 0) - throw new java.lang.UnsupportedOperationException("Native object address is NULL"); + throw new java.lang.UnsupportedOperationException("Native object address is nullptr"); nativeObj = addr; } diff --git a/modules/java/misc/detection/gen_dict.json b/modules/java/misc/detection/gen_dict.json index bd7de1194a..bdcae347cd 100644 --- a/modules/java/misc/detection/gen_dict.json +++ b/modules/java/misc/detection/gen_dict.json @@ -36,7 +36,7 @@ " try {", " LOGD(\"%s\", method_name);", " std::vector cMo_vec_list_arr;", - " vpDetectorAprilTag* me = (vpDetectorAprilTag*) self; //TODO: check for NULL", + " vpDetectorAprilTag* me = (vpDetectorAprilTag*) self; //TODO: check for nullptr", " vpImage& I = *((vpImage*)I_nativeObj);", " vpCameraParameters& cam = *((vpCameraParameters*)cam_nativeObj);", " /* bool _retval_ = */ me->detect( I, (double)tagSize, cam, cMo_vec_list_arr );", @@ -46,7 +46,7 @@ " } catch (...) {", " throwJavaException(env, 0, method_name);", " }", - " return NULL;", + " return nullptr;", "}\n\n", "//", "// manual port", @@ -59,7 +59,7 @@ " static const char method_name[] = \"detection::detect_11()\";", " try {", " LOGD(\"%s\", method_name);", - " vpDetectorAprilTag* me = (vpDetectorAprilTag*) self; //TODO: check for NULL", + " vpDetectorAprilTag* me = (vpDetectorAprilTag*) self; //TODO: check for nullptr", " vpImage& I = *((vpImage*)I_nativeObj);", " bool _retval_ = me->detect( I );", " return _retval_;", @@ -267,7 +267,7 @@ " vpDetectorAprilTag *tag = (vpDetectorAprilTag*) self;", " std::vector tag_ids = tag->getTagsId();", " jintArray jIds = env->NewIntArray(tag_ids.size());", - " jint *ptr_ids = NULL;", + " jint *ptr_ids = nullptr;", " ptr_ids = env->GetIntArrayElements(jIds, 0);", " for (size_t i = 0; i < tag_ids.size(); i++) {", " ptr_ids[i] = tag_ids[i];", diff --git a/modules/java/misc/imgproc/src/java/imgproc+VpContour.java b/modules/java/misc/imgproc/src/java/imgproc+VpContour.java index 31b9c1872f..36efebcb87 100644 --- a/modules/java/misc/imgproc/src/java/imgproc+VpContour.java +++ b/modules/java/misc/imgproc/src/java/imgproc+VpContour.java @@ -6,7 +6,7 @@ public class VpContour { public VpContour(long addr){ if (addr == 0) - throw new java.lang.UnsupportedOperationException("Native object address is NULL"); + throw new java.lang.UnsupportedOperationException("Native object address is nullptr"); nativeObj = addr; } diff --git a/modules/java/misc/mbt/gen_dict.json b/modules/java/misc/mbt/gen_dict.json index 62b13dc277..9e634f20ec 100644 --- a/modules/java/misc/mbt/gen_dict.json +++ b/modules/java/misc/mbt/gen_dict.json @@ -190,7 +190,7 @@ " static const char method_name[] = \"vpMbGenericTracker::getCameraParameters_10()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpCameraParameters& camera = *((vpCameraParameters*)camera_nativeObj);", " me->getCameraParameters( camera );", " } catch(const std::exception &e) {", @@ -210,7 +210,7 @@ " static const char method_name[] = \"vpMbGenericTracker::getCameraParameters_11()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpCameraParameters& cam1 = *((vpCameraParameters*)cam1_nativeObj);", " vpCameraParameters& cam2 = *((vpCameraParameters*)cam2_nativeObj);", " me->getCameraParameters( cam1, cam2 );", @@ -231,7 +231,7 @@ " static const char method_name[] = \"vpMbGenericTracker::getCameraParameters_12()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " int cameraCount = env->GetArrayLength(cameraNames);", " std::map mapOfCameraParameters;", " jlong *jcameras = env->GetLongArrayElements(cameras, 0);", @@ -299,7 +299,7 @@ " static const char method_name[] = \"vpMbGenericTracker::getPose_10()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpHomogeneousMatrix& cMo = *((vpHomogeneousMatrix*)cMo_nativeObj);", " me->getPose( cMo );", " } catch(const std::exception &e) {", @@ -319,7 +319,7 @@ " static const char method_name[] = \"vpMbGenericTracker::getPose_11()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpHomogeneousMatrix& c1Mo = *((vpHomogeneousMatrix*)c1Mo_nativeObj);", " vpHomogeneousMatrix& c2Mo = *((vpHomogeneousMatrix*)c2Mo_nativeObj);", " me->getPose( c1Mo, c2Mo );", @@ -340,7 +340,7 @@ " static const char method_name[] = \"vpMbGenericTracker::getPose_12()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " int cameraCount = env->GetArrayLength(cameraNames);", " std::map mapOfCameraPoses;", " jlong *jposes = env->GetLongArrayElements(poses, 0);", @@ -408,7 +408,7 @@ " static const char method_name[] = \"vpMbGenericTracker::initFromPose_10()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpImage& I = *((vpImage*)I_nativeObj);", " vpHomogeneousMatrix& cMo = *((vpHomogeneousMatrix*)cMo_nativeObj);", " me->initFromPose( I, cMo );", @@ -429,7 +429,7 @@ " static const char method_name[] = \"vpMbGenericTracker::initFromPose_11()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpImage& I1 = *((vpImage*)I1_nativeObj);", " vpImage& I2 = *((vpImage*)I2_nativeObj);", " vpHomogeneousMatrix& c1Mo = *((vpHomogeneousMatrix*)c1Mo_nativeObj);", @@ -452,7 +452,7 @@ " static const char method_name[] = \"vpMbGenericTracker::initFromPose_12()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* tracker = (vpMbGenericTracker*) address; //TODO: check for NULL", + " vpMbGenericTracker* tracker = (vpMbGenericTracker*) address; //TODO: check for nullptr", " int stringCount = env->GetArrayLength(cameraNames);", " std::map *> mapOfImages;", " std::map mapOfCameraPoses;", @@ -525,7 +525,7 @@ " static const char method_name[] = \"mbt::loadConfigFile_11()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " const char* utf_configFile = env->GetStringUTFChars(configFile, 0);", " string n_configFile( utf_configFile ? utf_configFile : \"\" );", " env->ReleaseStringUTFChars(configFile, utf_configFile);", @@ -547,7 +547,7 @@ " static const char method_name[] = \"mbt::loadConfigFile_10()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " const char* utf_configFile1 = env->GetStringUTFChars(configFile1, 0);", " string n_configFile1( utf_configFile1 ? utf_configFile1 : \"\" );", " env->ReleaseStringUTFChars(configFile1, utf_configFile1);", @@ -666,7 +666,7 @@ " static const char method_name[] = \"vpMbGenericTracker::loadModel()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " const char* utf_modelFile = env->GetStringUTFChars(modelFile, 0);", " string n_modelFile( utf_modelFile ? utf_modelFile : \"\" );", " env->ReleaseStringUTFChars(modelFile, utf_modelFile);", @@ -689,7 +689,7 @@ " static const char method_name[] = \"vpMbGenericTracker::loadModel()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " const char* utf_modelFile = env->GetStringUTFChars(modelFile, 0);", " string n_modelFile( utf_modelFile ? utf_modelFile : \"\" );", " env->ReleaseStringUTFChars(modelFile, utf_modelFile);", @@ -711,7 +711,7 @@ " static const char method_name[] = \"vpMbGenericTracker::loadModel()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " const char* utf_modelFile1 = env->GetStringUTFChars(modelFile1, 0);", " string n_modelFile1( utf_modelFile1 ? utf_modelFile1 : \"\" );", " env->ReleaseStringUTFChars(modelFile1, utf_modelFile1);", @@ -738,7 +738,7 @@ " static const char method_name[] = \"vpMbGenericTracker::loadModel()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " const char* utf_modelFile1 = env->GetStringUTFChars(modelFile1, 0);", " string n_modelFile1( utf_modelFile1 ? utf_modelFile1 : \"\" );", " env->ReleaseStringUTFChars(modelFile1, utf_modelFile1);", @@ -766,14 +766,14 @@ " vpMbGenericTracker *tracker = (vpMbGenericTracker*) address;", " int stringCount = env->GetArrayLength(stringKeys);", " int sizeT = env->GetArrayLength(Ts);", - " jlong *jTs = sizeT > 0 ? env->GetLongArrayElements(Ts, 0) : NULL;", + " jlong *jTs = sizeT > 0 ? env->GetLongArrayElements(Ts, 0) : nullptr;", " std::map map;", " std::map mapOfT;", " for (int i = 0; i < stringCount; i++) {", " jstring key = (jstring) (env->GetObjectArrayElement(stringKeys, i));", " jstring value = (jstring) (env->GetObjectArrayElement(stringValues, i));", " map[convertTo(env, key)] = convertTo(env, value);", - " if (jTs != NULL) {", + " if (jTs != nullptr) {", " vpHomogeneousMatrix& T = *((vpHomogeneousMatrix*)jTs[i]);", " mapOfT[convertTo(env, key)] = T;", " }", @@ -869,7 +869,7 @@ " static const char method_name[] = \"vpMbGenericTracker::track_10()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpImage& I = *((vpImage*)I_nativeObj);", " me->track( I );", " return;", @@ -890,7 +890,7 @@ " static const char method_name[] = \"vpMbGenericTracker::track_11()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* me = (vpMbGenericTracker*) self; //TODO: check for nullptr", " vpImage& I1 = *((vpImage*)I1_nativeObj);", " vpImage& I2 = *((vpImage*)I2_nativeObj);", " me->track( I1, I2 );", @@ -912,7 +912,7 @@ " static const char method_name[] = \"vpMbGenericTracker::track_12()\";", " try {", " LOGD(\"%s\", method_name);", - " vpMbGenericTracker* tracker = (vpMbGenericTracker*) self; //TODO: check for NULL", + " vpMbGenericTracker* tracker = (vpMbGenericTracker*) self; //TODO: check for nullptr", " int cameraNamesCount = env->GetArrayLength(cameraNames);", " jlong *jlong_images = env->GetLongArrayElements(images, 0);", " std::map *> mapOfImages;", @@ -1029,7 +1029,7 @@ "jn_code": [ "" ] - }, + }, "getKltMaskBorder": { "j_code": [ "" diff --git a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h index f2fac6d886..3bb77f9b16 100644 --- a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h +++ b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h @@ -349,7 +349,7 @@ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, pu { (reinterpret_cast(arg))->updateArticularPosition(); // pthread_exit((void*) 0); - return NULL; + return nullptr; } #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h index 3a38780376..0e2bde3196 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h +++ b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h @@ -226,7 +226,7 @@ class VISP_EXPORT vpSimulatorAfma6 : public vpRobotWireFrameSimulator, public vp double pos5, double pos6); void setPosition(const char *filename); void setPositioningVelocity(double vel) { positioningVelocity = vel; } - bool setPosition(const vpHomogeneousMatrix &cdMo, vpImage *Iint = NULL, const double &errMax = 0.001); + bool setPosition(const vpHomogeneousMatrix &cdMo, vpImage *Iint = nullptr, const double &errMax = 0.001); vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) override; void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) override; diff --git a/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp b/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp index 71310ae2a4..de7ed643db 100644 --- a/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp +++ b/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp @@ -49,7 +49,7 @@ * Authorize indexing on all movements by default. */ vpVirtuose::vpVirtuose() - : m_virtContext(NULL), m_ip_port("localhost#5000"), m_verbose(false), m_apiMajorVersion(0), m_apiMinorVersion(0), + : m_virtContext(nullptr), m_ip_port("localhost#5000"), m_verbose(false), m_apiMajorVersion(0), m_apiMinorVersion(0), m_ctrlMajorVersion(0), m_ctrlMinorVersion(0), m_typeCommand(COMMAND_TYPE_IMPEDANCE), m_indexType(INDEXING_ALL), m_is_init(false), m_period(0.001f), m_njoints(6) { @@ -62,9 +62,9 @@ vpVirtuose::vpVirtuose() */ void vpVirtuose::close() { - if (m_virtContext != NULL) { + if (m_virtContext != nullptr) { virtClose(m_virtContext); - m_virtContext = NULL; + m_virtContext = nullptr; } } @@ -538,7 +538,7 @@ void vpVirtuose::init() if (!m_is_init) { m_virtContext = virtOpen(m_ip_port.c_str()); - if (m_virtContext == NULL) { + if (m_virtContext == nullptr) { int err = virtGetErrorCode(m_virtContext); throw(vpException(vpException::fatalError, "Cannot open communication with haptic device using %s: %s. Check ip and port values", diff --git a/modules/robot/src/image-simulator/vpImageSimulator.cpp b/modules/robot/src/image-simulator/vpImageSimulator.cpp index f35cdcdc13..d71babc2db 100644 --- a/modules/robot/src/image-simulator/vpImageSimulator.cpp +++ b/modules/robot/src/image-simulator/vpImageSimulator.cpp @@ -57,8 +57,8 @@ */ vpImageSimulator::vpImageSimulator(const vpColorPlan &col) : cMt(), pt(), ptClipped(), interp(SIMPLE), normal_obj(), normal_Cam(), normal_Cam_optim(), distance(1.), - visible_result(1.), visible(false), X0_2_optim(NULL), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), - vbase_v(), vbase_u_optim(NULL), vbase_v_optim(NULL), Xinter_optim(NULL), listTriangle(), colorI(col), Ig(), Ic(), + visible_result(1.), visible(false), X0_2_optim(nullptr), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), + vbase_v(), vbase_u_optim(nullptr), vbase_v_optim(nullptr), Xinter_optim(nullptr), listTriangle(), colorI(col), Ig(), Ic(), rect(), cleanPrevImage(false), setBackgroundTexture(false), bgColor(vpColor::white), focal(), needClipping(false) { for (int i = 0; i < 4; i++) @@ -94,8 +94,8 @@ vpImageSimulator::vpImageSimulator(const vpColorPlan &col) */ vpImageSimulator::vpImageSimulator(const vpImageSimulator &text) : cMt(), pt(), ptClipped(), interp(SIMPLE), normal_obj(), normal_Cam(), normal_Cam_optim(), distance(1.), - visible_result(1.), visible(false), X0_2_optim(NULL), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), - vbase_v(), vbase_u_optim(NULL), vbase_v_optim(NULL), Xinter_optim(NULL), listTriangle(), colorI(GRAY_SCALED), Ig(), + visible_result(1.), visible(false), X0_2_optim(nullptr), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), + vbase_v(), vbase_u_optim(nullptr), vbase_v_optim(nullptr), Xinter_optim(nullptr), listTriangle(), colorI(GRAY_SCALED), Ig(), Ic(), rect(), cleanPrevImage(false), setBackgroundTexture(false), bgColor(vpColor::white), focal(), needClipping(false) { diff --git a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp index f5cc6d3f3f..c79d06eb55 100644 --- a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp @@ -161,8 +161,9 @@ vpRobotAfma4::vpRobotAfma4(bool verbose) : vpAfma4(), vpRobot() try { this->init(); this->setRobotState(vpRobot::STATE_STOP); - } catch (...) { - // vpERROR_TRACE("Error caught") ; + } + catch (...) { + // vpERROR_TRACE("Error caught") ; throw; } positioningVelocity = defaultPositioningVelocity; @@ -220,7 +221,7 @@ void vpRobotAfma4::init(void) // Look if the power is on or off UInt32 HIPowerStatus; UInt32 EStopStatus; - Try(PrimitiveSTATUS_Afma4(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma4(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // Print the robot status @@ -293,7 +294,7 @@ vpRobotAfma4::~vpRobotAfma4(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Afma4(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma4(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // if (HIPowerStatus == 1) { @@ -333,9 +334,10 @@ vpRobot::vpRobotStateType vpRobotAfma4::setRobotState(vpRobot::vpRobotStateType if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; Try(PrimitiveSTOP_Afma4()); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } this->powerOn(); break; @@ -400,23 +402,26 @@ void vpRobotAfma4::powerOn(void) unsigned int nitermax = 10; for (unsigned int i = 0; i < nitermax; i++) { - Try(PrimitiveSTATUS_Afma4(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma4(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); if (EStopStatus == ESTOP_AUTO) { break; // exit for loop - } else if (EStopStatus == ESTOP_MANUAL) { + } + else if (EStopStatus == ESTOP_MANUAL) { break; // exit for loop - } else if (EStopStatus == ESTOP_ACTIVATED) { + } + else if (EStopStatus == ESTOP_ACTIVATED) { if (firsttime) { std::cout << "Emergency stop is activated! \n" - << "Check the emergency stop button and push the yellow " - "button before continuing." - << std::endl; + << "Check the emergency stop button and push the yellow " + "button before continuing." + << std::endl; firsttime = false; } fprintf(stdout, "Remaining time %us \r", nitermax - i); fflush(stdout); CAL_Wait(1); - } else { + } + else { std::cout << "Sorry there is an error on the emergency chain." << std::endl; std::cout << "You have to call Adept for maintenance..." << std::endl; // Free allocated resources @@ -462,7 +467,7 @@ void vpRobotAfma4::powerOff(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Afma4(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma4(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -496,7 +501,7 @@ bool vpRobotAfma4::getPowerState(void) bool status = false; // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Afma4(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma4(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -552,7 +557,8 @@ void vpRobotAfma4::get_cVf(vpVelocityTwistMatrix &cVf) const try { vpAfma4::get_cVf(q, cVf); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -598,7 +604,8 @@ void vpRobotAfma4::get_eJe(vpMatrix &eJe) try { vpAfma4::get_eJe(q, eJe); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -633,7 +640,8 @@ void vpRobotAfma4::get_fJe(vpMatrix &fJe) try { vpAfma4::get_fJe(q, fJe); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -867,7 +875,8 @@ void vpRobotAfma4::setPosition(const vpRobot::vpControlFrameType frame, const do position[3] = q5; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1188,10 +1197,10 @@ void vpRobotAfma4::setVelocity(const vpRobot::vpControlFrameType frame, const vp vpColVector velocity = vpRobot::saturateVelocities(vel, vel_max, true); #if 0 // ok - vpMatrix eJe(4,6); + vpMatrix eJe(4, 6); eJe = 0; eJe[2][4] = -1; - eJe[3][3] = 1; + eJe[3][3] = 1; joint_vel = eJe * velocity; // Compute the articular velocity #endif @@ -1240,17 +1249,19 @@ void vpRobotAfma4::setVelocity(const vpRobot::vpControlFrameType frame, const vp if (TryStt < 0) { if (TryStt == VelStopOnJoint) { UInt32 axisInJoint[njoint]; - PrimitiveSTATUS_Afma4(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL); + PrimitiveSTATUS_Afma4(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr); for (unsigned int i = 0; i < njoint; i++) { if (axisInJoint[i]) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; } - } else { + } + else { printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt); - if (TryString != NULL) { + if (TryString != nullptr) { // The statement is in TryString, but we need to check the validity printf(" Error sentence %s\n", TryString); // Print the TryString - } else { + } + else { printf("\n"); } } @@ -1388,7 +1399,8 @@ void vpRobotAfma4::getVelocity(const vpRobot::vpControlFrameType frame, vpColVec break; } } - } else { + } + else { first_time_getvel = false; } @@ -1625,7 +1637,7 @@ bool vpRobotAfma4::savePosFile(const std::string &filename, const vpColVector &q FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "\ @@ -1726,7 +1738,8 @@ void vpRobotAfma4::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto return; } } - } else { + } + else { first_time_getdis = false; } @@ -1743,5 +1756,5 @@ void vpRobotAfma4::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotAfma4.cpp.o) has no // symbols -void dummy_vpRobotAfma4(){}; +void dummy_vpRobotAfma4() { }; #endif diff --git a/modules/robot/src/real-robot/afma4/vpServolens.cpp b/modules/robot/src/real-robot/afma4/vpServolens.cpp index 226746015d..f4a8bc9fa0 100644 --- a/modules/robot/src/real-robot/afma4/vpServolens.cpp +++ b/modules/robot/src/real-robot/afma4/vpServolens.cpp @@ -715,7 +715,7 @@ bool vpServolens::read(char *c, long timeout_s) const FD_ZERO(&readfds); FD_SET(static_cast(this->remfd), &readfds); - if (select(FD_SETSIZE, &readfds, (fd_set *)NULL, (fd_set *)NULL, &timeout) > 0) { + if (select(FD_SETSIZE, &readfds, (fd_set *)nullptr, (fd_set *)nullptr, &timeout) > 0) { ssize_t n = ::read(this->remfd, c, 1); /* read one character at a time */ if (n != 1) return false; diff --git a/modules/robot/src/real-robot/afma6/vpAfma6.cpp b/modules/robot/src/real-robot/afma6/vpAfma6.cpp index 2ead7b326c..600ee8e7cc 100644 --- a/modules/robot/src/real-robot/afma6/vpAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpAfma6.cpp @@ -59,7 +59,7 @@ /* ---------------------------------------------------------------------- */ static const char *opt_Afma6[] = {"JOINT_MAX", "JOINT_MIN", "LONG_56", "COUPL_56", - "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", NULL}; + "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr}; #ifdef VISP_HAVE_AFMA6_DATA const std::string vpAfma6::CONST_AFMA6_FILENAME = @@ -1116,7 +1116,7 @@ void vpAfma6::parseConfigFile(const std::string &filename) std::string key; ss >> key; - for (code = 0; NULL != opt_Afma6[code]; ++code) { + for (code = 0; nullptr != opt_Afma6[code]; ++code) { if (key.compare(opt_Afma6[code]) == 0) { break; } diff --git a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp index 24ed3560b5..80f1a4d1f9 100644 --- a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp @@ -250,7 +250,7 @@ void vpRobotAfma6::init(void) // Look if the power is on or off UInt32 HIPowerStatus; UInt32 EStopStatus; - Try(PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // Print the robot status @@ -562,7 +562,7 @@ vpRobotAfma6::~vpRobotAfma6(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // if (HIPowerStatus == 1) { @@ -669,7 +669,7 @@ void vpRobotAfma6::powerOn(void) unsigned int nitermax = 10; for (unsigned int i = 0; i < nitermax; i++) { - Try(PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); if (EStopStatus == ESTOP_AUTO) { break; // exit for loop } else if (EStopStatus == ESTOP_MANUAL) { @@ -731,7 +731,7 @@ void vpRobotAfma6::powerOff(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -765,7 +765,7 @@ bool vpRobotAfma6::getPowerState(void) bool status = false; // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -1669,14 +1669,14 @@ void vpRobotAfma6::setVelocity(const vpRobot::vpControlFrameType frame, const vp if (TryStt < 0) { if (TryStt == VelStopOnJoint) { Int32 axisInJoint[njoint]; - PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL); + PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr); for (unsigned int i = 0; i < njoint; i++) { if (axisInJoint[i]) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; } } else { printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt); - if (TryString != NULL) { + if (TryString != nullptr) { // The statement is in TryString, but we need to check the validity printf(" Error sentence %s\n", TryString); // Print the TryString } else { @@ -2061,7 +2061,7 @@ bool vpRobotAfma6::savePosFile(const std::string &filename, const vpColVector &q FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "\ @@ -2273,7 +2273,7 @@ bool vpRobotAfma6::checkJointLimits(vpColVector &jointsStatus) jointsStatus.resize(6); InitTry; - Try(PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL)); + Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr)); for (unsigned int i = 0; i < njoint; i++) { if (axisInJoint[i]) { std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; diff --git a/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp b/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp index 73ccb914a1..45d99cb07c 100644 --- a/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp +++ b/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp @@ -73,7 +73,7 @@ extern "C" { */ bool vpRobotBebop2::m_running = false; -ARCONTROLLER_Device_t *vpRobotBebop2::m_deviceController = NULL; +ARCONTROLLER_Device_t *vpRobotBebop2::m_deviceController = nullptr; /*! @@ -123,12 +123,12 @@ vpRobotBebop2::vpRobotBebop2(bool verbose, bool setDefaultSettings, std::string sigaction(SIGQUIT, &m_sigAct, 0); #ifdef VISP_HAVE_FFMPEG - m_codecContext = NULL; + m_codecContext = nullptr; m_packet = AVPacket(); - m_picture = NULL; - m_bgr_picture = NULL; - m_img_convert_ctx = NULL; - m_buffer = NULL; + m_picture = nullptr; + m_bgr_picture = nullptr; + m_img_convert_ctx = nullptr; + m_buffer = nullptr; m_videoDecodingStarted = false; #endif @@ -220,7 +220,7 @@ vpRobotBebop2::~vpRobotBebop2() { cleanUp(); } */ void vpRobotBebop2::doFlatTrim() { - if (isRunning() && m_deviceController != NULL && isLanded()) { + if (isRunning() && m_deviceController != nullptr && isLanded()) { m_flatTrimFinished = false; @@ -317,7 +317,7 @@ double vpRobotBebop2::getMaxCameraPan() const { return m_maxCameraPan; } */ void vpRobotBebop2::setCameraOrientation(double tilt, double pan, bool blocking) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { m_deviceController->aRDrone3->sendCameraOrientationV2(m_deviceController->aRDrone3, static_cast(tilt), static_cast(pan)); @@ -346,7 +346,7 @@ void vpRobotBebop2::setCameraOrientation(double tilt, double pan, bool blocking) */ void vpRobotBebop2::setCameraTilt(double tilt, bool blocking) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { m_deviceController->aRDrone3->sendCameraOrientationV2(m_deviceController->aRDrone3, static_cast(tilt), static_cast(getCurrentCameraPan())); @@ -375,7 +375,7 @@ void vpRobotBebop2::setCameraTilt(double tilt, bool blocking) */ void vpRobotBebop2::setCameraPan(double pan, bool blocking) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { m_deviceController->aRDrone3->sendCameraOrientationV2( m_deviceController->aRDrone3, static_cast(getCurrentCameraTilt()), static_cast(pan)); @@ -397,7 +397,7 @@ void vpRobotBebop2::setCameraPan(double pan, bool blocking) */ bool vpRobotBebop2::isRunning() { - if (m_deviceController == NULL) { + if (m_deviceController == nullptr) { return false; } else { return m_running; @@ -453,7 +453,7 @@ bool vpRobotBebop2::isLanded() */ void vpRobotBebop2::takeOff(bool blocking) { - if (isRunning() && isLanded() && m_deviceController != NULL) { + if (isRunning() && isLanded() && m_deviceController != nullptr) { m_deviceController->aRDrone3->sendPilotingTakeOff(m_deviceController->aRDrone3); @@ -476,7 +476,7 @@ void vpRobotBebop2::takeOff(bool blocking) */ void vpRobotBebop2::land() { - if (m_deviceController != NULL) { + if (m_deviceController != nullptr) { m_deviceController->aRDrone3->sendPilotingLanding(m_deviceController->aRDrone3); } } @@ -493,7 +493,7 @@ void vpRobotBebop2::land() */ void vpRobotBebop2::setVerticalSpeed(int value) { - if (isRunning() && m_deviceController != NULL && (isFlying() || isHovering())) { + if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) { m_errorController = m_deviceController->aRDrone3->setPilotingPCMDGaz(m_deviceController->aRDrone3, static_cast(value)); @@ -519,7 +519,7 @@ void vpRobotBebop2::setVerticalSpeed(int value) */ void vpRobotBebop2::setYawSpeed(int value) { - if (isRunning() && m_deviceController != NULL && (isFlying() || isHovering())) { + if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) { m_errorController = m_deviceController->aRDrone3->setPilotingPCMDYaw(m_deviceController->aRDrone3, static_cast(value)); @@ -546,7 +546,7 @@ void vpRobotBebop2::setYawSpeed(int value) */ void vpRobotBebop2::setPitch(int value) { - if (isRunning() && m_deviceController != NULL && (isFlying() || isHovering())) { + if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) { m_errorController = m_deviceController->aRDrone3->setPilotingPCMDPitch(m_deviceController->aRDrone3, static_cast(value)); @@ -574,7 +574,7 @@ void vpRobotBebop2::setPitch(int value) */ void vpRobotBebop2::setRoll(int value) { - if (isRunning() && m_deviceController != NULL && (isFlying() || isHovering())) { + if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) { m_errorController = m_deviceController->aRDrone3->setPilotingPCMDRoll(m_deviceController->aRDrone3, static_cast(value)); @@ -598,7 +598,7 @@ void vpRobotBebop2::setRoll(int value) */ void vpRobotBebop2::cutMotors() { - if (m_deviceController != NULL) { + if (m_deviceController != nullptr) { m_errorController = m_deviceController->aRDrone3->sendPilotingEmergency(m_deviceController->aRDrone3); } } @@ -620,7 +620,7 @@ void vpRobotBebop2::cutMotors() */ void vpRobotBebop2::setPosition(float dX, float dY, float dZ, float dPsi, bool blocking) { - if (isRunning() && m_deviceController != NULL && (isFlying() || isHovering())) { + if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) { m_relativeMoveEnded = false; m_deviceController->aRDrone3->sendPilotingMoveBy(m_deviceController->aRDrone3, dX, dY, dZ, dPsi); @@ -721,7 +721,7 @@ void vpRobotBebop2::setVerbose(bool verbose) */ void vpRobotBebop2::resetAllSettings() { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { m_settingsReset = false; m_deviceController->common->sendSettingsReset(m_deviceController->common); @@ -748,7 +748,7 @@ void vpRobotBebop2::resetAllSettings() */ void vpRobotBebop2::setMaxTilt(double maxTilt) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { m_deviceController->aRDrone3->sendPilotingSettingsMaxTilt(m_deviceController->aRDrone3, static_cast(maxTilt)); } else { @@ -765,7 +765,7 @@ void vpRobotBebop2::setMaxTilt(double maxTilt) */ void vpRobotBebop2::stopMoving() { - if (isRunning() && !isLanded() && m_deviceController != NULL) { + if (isRunning() && !isLanded() && m_deviceController != nullptr) { m_errorController = m_deviceController->aRDrone3->setPilotingPCMD(m_deviceController->aRDrone3, 0, 0, 0, 0, 0, 0); } } @@ -788,7 +788,7 @@ void vpRobotBebop2::getGrayscaleImage(vpImage &I) { if (m_videoDecodingStarted) { - if (m_bgr_picture->data[0] != NULL) { + if (m_bgr_picture->data[0] != nullptr) { I.resize(static_cast(m_videoHeight), static_cast(m_videoWidth)); m_bgr_picture_mutex.lock(); @@ -796,7 +796,7 @@ void vpRobotBebop2::getGrayscaleImage(vpImage &I) I.getHeight()); m_bgr_picture_mutex.unlock(); } else { - ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Error while getting current grayscale image : image data is NULL"); + ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Error while getting current grayscale image : image data is nullptr"); } } else { @@ -816,7 +816,7 @@ void vpRobotBebop2::getRGBaImage(vpImage &I) { if (m_videoDecodingStarted) { - if (m_bgr_picture->data[0] != NULL) { + if (m_bgr_picture->data[0] != nullptr) { I.resize(static_cast(m_videoHeight), static_cast(m_videoWidth)); m_bgr_picture_mutex.lock(); @@ -824,7 +824,7 @@ void vpRobotBebop2::getRGBaImage(vpImage &I) I.getHeight()); m_bgr_picture_mutex.unlock(); } else { - ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Error while getting current RGBa image : image data is NULL"); + ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Error while getting current RGBa image : image data is nullptr"); } } else { @@ -855,7 +855,7 @@ int vpRobotBebop2::getVideoWidth() { return m_videoWidth; } */ void vpRobotBebop2::setExposure(float expo) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { expo = std::min(1.5f, std::max(-1.5f, expo)); m_exposureSet = false; @@ -886,7 +886,7 @@ void vpRobotBebop2::setExposure(float expo) */ void vpRobotBebop2::setStreamingMode(int mode) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { if (!isStreaming() && isLanded()) { eARCOMMANDS_ARDRONE3_MEDIASTREAMING_VIDEOSTREAMMODE_MODE cmd_mode = @@ -935,7 +935,7 @@ void vpRobotBebop2::setStreamingMode(int mode) */ void vpRobotBebop2::setVideoResolution(int mode) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { if (!isStreaming() && isLanded()) { @@ -988,7 +988,7 @@ void vpRobotBebop2::setVideoResolution(int mode) */ void vpRobotBebop2::setVideoStabilisationMode(int mode) { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { eARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE_NONE; @@ -1027,7 +1027,7 @@ void vpRobotBebop2::setVideoStabilisationMode(int mode) */ void vpRobotBebop2::startStreaming() { - if (isRunning() && m_deviceController != NULL) { + if (isRunning() && m_deviceController != nullptr) { ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Starting video streaming ... "); // Sending command to the drone to start the video stream @@ -1062,7 +1062,7 @@ void vpRobotBebop2::startStreaming() */ void vpRobotBebop2::stopStreaming() { - if (m_videoDecodingStarted && m_deviceController != NULL) { + if (m_videoDecodingStarted && m_deviceController != nullptr) { ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Stopping video streaming ... "); // Sending command to the drone to stop the video stream @@ -1122,7 +1122,7 @@ void vpRobotBebop2::sighandler(int signo) vpRobotBebop2::m_running = false; // Landing the drone - if (m_deviceController != NULL) { + if (m_deviceController != nullptr) { m_deviceController->aRDrone3->sendPilotingLanding(m_deviceController->aRDrone3); } std::exit(EXIT_FAILURE); @@ -1134,7 +1134,7 @@ void vpRobotBebop2::sighandler(int signo) */ eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE vpRobotBebop2::getFlyingState() { - if (m_deviceController != NULL) { + if (m_deviceController != nullptr) { eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE flyingState = ARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE_MAX; eARCONTROLLER_ERROR error; @@ -1142,19 +1142,19 @@ eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE vpRobotBebop2::getFl ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary = ARCONTROLLER_ARDrone3_GetCommandElements( m_deviceController->aRDrone3, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED, &error); - if (error == ARCONTROLLER_OK && elementDictionary != NULL) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + if (error == ARCONTROLLER_OK && elementDictionary != nullptr) { + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { // Suppress warnings // Get the value HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE, arg); - if (arg != NULL) { + if (arg != nullptr) { // Enums are stored as I32 flyingState = static_cast(arg->value.I32); } @@ -1173,7 +1173,7 @@ eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE vpRobotBebop2::getFl */ eARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED vpRobotBebop2::getStreamingState() { - if (m_deviceController != NULL) { + if (m_deviceController != nullptr) { eARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED streamingState = ARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED_MAX; eARCONTROLLER_ERROR error; @@ -1182,18 +1182,18 @@ eARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED vpRobotBebop m_deviceController->aRDrone3, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED, &error); - if (error == ARCONTROLLER_OK && elementDictionary != NULL) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + if (error == ARCONTROLLER_OK && elementDictionary != nullptr) { + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { // Get the value HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED, arg); - if (arg != NULL) { + if (arg != nullptr) { // Enums are stored as I32 streamingState = static_cast(arg->value.I32); @@ -1267,7 +1267,7 @@ void vpRobotBebop2::setupCallbacks() #ifdef VISP_HAVE_FFMPEG // Adding frame received callback, called when a streaming frame has been received from the device m_errorController = ARCONTROLLER_Device_SetVideoStreamCallbacks(m_deviceController, decoderConfigCallback, - didReceiveFrameCallback, NULL, this); + didReceiveFrameCallback, nullptr, this); if (m_errorController != ARCONTROLLER_OK) { ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error: %s", ARCONTROLLER_Error_ToString(m_errorController)); @@ -1348,7 +1348,7 @@ void vpRobotBebop2::initCodec() m_codecContext->flags2 |= AV_CODEC_FLAG2_CHUNKS; // Opens the codec - if (avcodec_open2(m_codecContext, codec, NULL) < 0) { + if (avcodec_open2(m_codecContext, codec, nullptr) < 0) { ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Failed to open codec."); return; } @@ -1365,8 +1365,8 @@ void vpRobotBebop2::initCodec() m_bgr_picture_mutex.unlock(); m_img_convert_ctx = sws_getContext(m_codecContext->width, m_codecContext->height, m_codecContext->pix_fmt, - m_codecContext->width, m_codecContext->height, pFormat, SWS_BICUBIC, NULL, NULL, - NULL); // Used to rescale frame received from the decoder + m_codecContext->width, m_codecContext->height, pFormat, SWS_BICUBIC, nullptr, nullptr, + nullptr); // Used to rescale frame received from the decoder } /*! @@ -1524,7 +1524,7 @@ void vpRobotBebop2::computeFrame(ARCONTROLLER_Frame_t *frame) */ void vpRobotBebop2::cleanUp() { - if (m_deviceController != NULL) { + if (m_deviceController != nullptr) { // Lands the drone if not landed land(); @@ -1646,14 +1646,14 @@ eARCONTROLLER_ERROR vpRobotBebop2::didReceiveFrameCallback(ARCONTROLLER_Frame_t { vpRobotBebop2 *drone = static_cast(customData); - if (frame != NULL) { + if (frame != nullptr) { if (drone->m_videoDecodingStarted) { drone->computeFrame(frame); } } else { - ARSAL_PRINT(ARSAL_PRINT_WARNING, TAG, "frame is NULL."); + ARSAL_PRINT(ARSAL_PRINT_WARNING, TAG, "frame is nullptr."); } return ARCONTROLLER_OK; @@ -1672,19 +1672,19 @@ eARCONTROLLER_ERROR vpRobotBebop2::didReceiveFrameCallback(ARCONTROLLER_Frame_t void vpRobotBebop2::cmdBatteryStateChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *singleElement = NULL; + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *singleElement = nullptr; - if (elementDictionary == NULL) { - ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "elements is NULL"); + if (elementDictionary == nullptr) { + ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "elements is nullptr"); return; } // Get the command received in the device controller HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, singleElement); - if (singleElement == NULL) { - ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "singleElement is NULL"); + if (singleElement == nullptr) { + ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "singleElement is nullptr"); return; } @@ -1692,8 +1692,8 @@ void vpRobotBebop2::cmdBatteryStateChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t HASH_FIND_STR(singleElement->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_BATTERYSTATECHANGED_PERCENT, arg); - if (arg == NULL) { - ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "arg is NULL"); + if (arg == nullptr) { + ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "arg is nullptr"); return; } drone->m_batteryLevel = arg->value.U8; @@ -1719,18 +1719,18 @@ void vpRobotBebop2::cmdBatteryStateChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t void vpRobotBebop2::cmdCameraOrientationChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_CAMERASTATE_ORIENTATIONV2_TILT, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_currentCameraTilt = static_cast(arg->value.Float); } HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_CAMERASTATE_ORIENTATIONV2_PAN, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_currentCameraPan = static_cast(arg->value.Float); } } @@ -1749,41 +1749,41 @@ void vpRobotBebop2::cmdCameraOrientationChangedRcv(ARCONTROLLER_DICTIONARY_ELEME */ void vpRobotBebop2::cmdCameraSettingsRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_FOV, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_cameraHorizontalFOV = static_cast(arg->value.Float); ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Camera horizontal FOV : %f degrees.", static_cast(drone->m_cameraHorizontalFOV)); } HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_PANMAX, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_maxCameraPan = static_cast(arg->value.Float); ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Max camera pan : %f degrees.", static_cast(drone->m_maxCameraPan)); } HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_PANMIN, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_minCameraPan = static_cast(arg->value.Float); ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Min camera pan : %f degrees.", static_cast(drone->m_minCameraPan)); } HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_TILTMAX, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_maxCameraTilt = static_cast(arg->value.Float); ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Max camera tilt : %f degrees.", static_cast(drone->m_maxCameraTilt)); } HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_TILTMIN, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_minCameraTilt = static_cast(arg->value.Float); ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Min camera tilt : %f degrees.", static_cast(drone->m_minCameraTilt)); @@ -1804,14 +1804,14 @@ void vpRobotBebop2::cmdCameraSettingsRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elem void vpRobotBebop2::cmdMaxPitchRollChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSETTINGSSTATE_MAXTILTCHANGED_CURRENT, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_maxTilt = static_cast(arg->value.Float); } } @@ -1829,15 +1829,15 @@ void vpRobotBebop2::cmdMaxPitchRollChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t */ void vpRobotBebop2::cmdRelativeMoveEndedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR, arg); - if (arg != NULL) { + if (arg != nullptr) { eARCOMMANDS_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR error = static_cast(arg->value.I32); if ((error != ARCOMMANDS_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR_OK) && @@ -1861,17 +1861,17 @@ void vpRobotBebop2::cmdRelativeMoveEndedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *e */ void vpRobotBebop2::cmdExposureSetRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone) { - ARCONTROLLER_DICTIONARY_ARG_t *arg = NULL; - ARCONTROLLER_DICTIONARY_ELEMENT_t *element = NULL; + ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr; + ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr; HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element); - if (element != NULL) { + if (element != nullptr) { HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PICTURESETTINGSSTATE_EXPOSITIONCHANGED_VALUE, arg); - if (arg != NULL) { + if (arg != nullptr) { drone->m_exposureSet = true; } } @@ -1891,7 +1891,7 @@ void vpRobotBebop2::commandReceivedCallback(eARCONTROLLER_DICTIONARY_KEY command { vpRobotBebop2 *drone = static_cast(customData); - if (drone == NULL) + if (drone == nullptr) return; switch (commandKey) { diff --git a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp index 957f688d08..bf9231b1ac 100644 --- a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp +++ b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp @@ -53,7 +53,7 @@ #include vpRobotBiclops::vpRobotBiclopsController::vpRobotBiclopsController() - : m_biclops(), m_axisMask(0), m_panAxis(NULL), m_tiltAxis(NULL), m_vergeAxis(NULL), m_panProfile(), m_tiltProfile(), + : m_biclops(), m_axisMask(0), m_panAxis(nullptr), m_tiltAxis(nullptr), m_vergeAxis(nullptr), m_panProfile(), m_tiltProfile(), m_vergeProfile(), m_shm(), m_stopControllerThread(false) { m_axisMask = Biclops::PanMask + Biclops::TiltMask; //+ Biclops::VergeMask*/; // add this if you want verge. diff --git a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h index e44bf2296e..abdcff0d92 100644 --- a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h +++ b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h @@ -96,8 +96,8 @@ class VISP_EXPORT vpRobotBiclops::vpRobotBiclopsController // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpRobotBiclopsController(const vpRobotBiclopsController &) - // : m_biclops(), m_axisMask(0), m_panAxis(NULL), m_tiltAxis(NULL), - // m_vergeAxis(NULL), + // : m_biclops(), m_axisMask(0), m_panAxis(nullptr), m_tiltAxis(nullptr), + // m_vergeAxis(nullptr), // m_panProfile(), m_tiltProfile(), m_vergeProfile(), m_shm(), // m_stopControllerThread(false) // { diff --git a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp index 288e6ec518..893258a983 100644 --- a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp @@ -116,7 +116,7 @@ void vpRobotBiclops::init() { // test if the config file exists FILE *fd = fopen(m_configfile.c_str(), "r"); - if (fd == NULL) { + if (fd == nullptr) { vpCERROR << "Cannot open Biclops config file: " << m_configfile << std::endl; throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with biclops"); } diff --git a/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp b/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp index 1122542422..d427549854 100644 --- a/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp +++ b/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp @@ -107,7 +107,7 @@ void vpRobotFlirPtu::init() Default constructor. */ vpRobotFlirPtu::vpRobotFlirPtu() - : m_eMc(), m_cer(NULL), m_status(0), m_pos_max_tics(2), m_pos_min_tics(2), m_vel_max_tics(2), m_res(2), + : m_eMc(), m_cer(nullptr), m_status(0), m_pos_max_tics(2), m_pos_min_tics(2), m_vel_max_tics(2), m_res(2), m_connected(false), m_njoints(2), m_positioning_velocity(20.) { signal(SIGINT, vpRobotFlirPtu::emergencyStop); @@ -499,8 +499,8 @@ void vpRobotFlirPtu::setPosition(const vpRobot::vpControlFrameType frame, const vpMath::deg(q[1]))); } - if (cpi_block_until(m_cer, NULL, NULL, OP_PAN_CURRENT_POS_GET, pos_tics[0]) || - cpi_block_until(m_cer, NULL, NULL, OP_TILT_CURRENT_POS_GET, pos_tics[1])) { + if (cpi_block_until(m_cer, nullptr, nullptr, OP_PAN_CURRENT_POS_GET, pos_tics[0]) || + cpi_block_until(m_cer, nullptr, nullptr, OP_TILT_CURRENT_POS_GET, pos_tics[1])) { disconnect(); throw(vpException(vpException::fatalError, "FLIR PTU failed to wait until position %d, %d reached (deg)", vpMath::deg(q[0]), vpMath::deg(q[1]))); @@ -538,7 +538,7 @@ void vpRobotFlirPtu::connect(const std::string &portname, int baudrate) throw(vpException(vpException::fatalError, "Port name is required to connect to FLIR PTU.")); } - if ((m_cer = (struct cerial *)malloc(sizeof(struct cerial))) == NULL) { + if ((m_cer = (struct cerial *)malloc(sizeof(struct cerial))) == nullptr) { disconnect(); throw(vpException(vpException::fatalError, "Out of memory during FLIR PTU connection.")); } @@ -559,7 +559,7 @@ void vpRobotFlirPtu::connect(const std::string &portname, int baudrate) cerioctl(m_cer, CERIAL_IOCTL_BAUDRATE_SET, &baudrate); // Flush any characters already buffered - cerioctl(m_cer, CERIAL_IOCTL_FLUSH_INPUT, NULL); + cerioctl(m_cer, CERIAL_IOCTL_FLUSH_INPUT, nullptr); // Set two second timeout */ int timeout = 2000; @@ -596,10 +596,10 @@ void vpRobotFlirPtu::connect(const std::string &portname, int baudrate) */ void vpRobotFlirPtu::disconnect() { - if (m_cer != NULL) { + if (m_cer != nullptr) { cerclose(m_cer); free(m_cer); - m_cer = NULL; + m_cer = nullptr; m_connected = false; } } @@ -832,7 +832,7 @@ void vpRobotFlirPtu::reset() return; } - if (cpi_ptcmd(m_cer, &m_status, OP_RESET, NULL)) { + if (cpi_ptcmd(m_cer, &m_status, OP_RESET, nullptr)) { throw(vpException(vpException::fatalError, "Unable to reset PTU.")); } } @@ -850,7 +850,7 @@ void vpRobotFlirPtu::stopMotion() return; } - if (cpi_ptcmd(m_cer, &m_status, OP_HALT, NULL)) { + if (cpi_ptcmd(m_cer, &m_status, OP_HALT, nullptr)) { throw(vpException(vpException::fatalError, "Unable to stop PTU.")); } } @@ -868,7 +868,7 @@ std::string vpRobotFlirPtu::getNetworkIP() } char str[64]; - if (cpi_ptcmd(m_cer, &m_status, OP_NET_IP_GET, (int)sizeof(str), NULL, &str)) { + if (cpi_ptcmd(m_cer, &m_status, OP_NET_IP_GET, (int)sizeof(str), nullptr, &str)) { throw(vpException(vpException::fatalError, "Unable to get Network IP.")); } @@ -888,7 +888,7 @@ std::string vpRobotFlirPtu::getNetworkGateway() } char str[64]; - if (cpi_ptcmd(m_cer, &m_status, OP_NET_GATEWAY_GET, (int)sizeof(str), NULL, &str)) { + if (cpi_ptcmd(m_cer, &m_status, OP_NET_GATEWAY_GET, (int)sizeof(str), nullptr, &str)) { throw(vpException(vpException::fatalError, "Unable to get Network Gateway.")); } @@ -908,7 +908,7 @@ std::string vpRobotFlirPtu::getNetworkHostName() } char str[64]; - if (cpi_ptcmd(m_cer, &m_status, OP_NET_HOSTNAME_GET, (int)sizeof(str), NULL, &str)) { + if (cpi_ptcmd(m_cer, &m_status, OP_NET_HOSTNAME_GET, (int)sizeof(str), nullptr, &str)) { throw(vpException(vpException::fatalError, "Unable to get Network hostname.")); } diff --git a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp index 5579d4348e..66b0067f2b 100644 --- a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp +++ b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp @@ -51,7 +51,7 @@ */ vpRobotFranka::vpRobotFranka() - : vpRobot(), m_handler(NULL), m_gripper(NULL), m_model(NULL), m_positioningVelocity(20.), m_velControlThread(), + : vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(), m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(), m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(), m_ft_cart_des(), m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(), m_mutex(), m_eMc(), m_log_folder(), @@ -67,7 +67,7 @@ vpRobotFranka::vpRobotFranka() * be set when required. Setting realtime_config to kIgnore disables this behavior. */ vpRobotFranka::vpRobotFranka(const std::string &franka_address, franka::RealtimeConfig realtime_config) - : vpRobot(), m_handler(NULL), m_gripper(NULL), m_model(NULL), m_positioningVelocity(20.), m_velControlThread(), + : vpRobot(), m_handler(nullptr), m_gripper(nullptr), m_model(nullptr), m_positioningVelocity(20.), m_velControlThread(), m_velControlThreadIsRunning(false), m_velControlThreadStopAsked(false), m_dq_des(), m_v_cart_des(), m_ftControlThread(), m_ftControlThreadIsRunning(false), m_ftControlThreadStopAsked(false), m_tau_J_des(), m_ft_cart_des(), m_q_min(), m_q_max(), m_dq_max(), m_ddq_max(), m_robot_state(), m_mutex(), m_eMc(), m_log_folder(), @@ -1151,7 +1151,7 @@ bool vpRobotFranka::savePosFile(const std::string &filename, const vpColVector & FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "#PANDA - Joint position file\n" @@ -1195,7 +1195,7 @@ void vpRobotFranka::gripperHoming() if (m_franka_address.empty()) { throw(vpException(vpException::fatalError, "Cannot perform franka gripper homing without ip address")); } - if (m_gripper == NULL) + if (m_gripper == nullptr) m_gripper = new franka::Gripper(m_franka_address); m_gripper->homing(); @@ -1215,7 +1215,7 @@ int vpRobotFranka::gripperMove(double width) if (m_franka_address.empty()) { throw(vpException(vpException::fatalError, "Cannot open franka gripper without ip address")); } - if (m_gripper == NULL) + if (m_gripper == nullptr) m_gripper = new franka::Gripper(m_franka_address); // Check for the maximum grasping width. @@ -1254,7 +1254,7 @@ int vpRobotFranka::gripperOpen() if (m_franka_address.empty()) { throw(vpException(vpException::fatalError, "Cannot open franka gripper without ip address")); } - if (m_gripper == NULL) + if (m_gripper == nullptr) m_gripper = new franka::Gripper(m_franka_address); // Check for the maximum grasping width. @@ -1275,7 +1275,7 @@ void vpRobotFranka::gripperRelease() if (m_franka_address.empty()) { throw(vpException(vpException::fatalError, "Cannot release franka gripper without ip address")); } - if (m_gripper == NULL) + if (m_gripper == nullptr) m_gripper = new franka::Gripper(m_franka_address); m_gripper->stop(); @@ -1297,7 +1297,7 @@ void vpRobotFranka::gripperRelease() */ int vpRobotFranka::gripperGrasp(double grasping_width, double force) { - if (m_gripper == NULL) + if (m_gripper == nullptr) m_gripper = new franka::Gripper(m_franka_address); // Check for the maximum grasping width. diff --git a/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp b/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp index 991c18b15c..0b82a0095e 100644 --- a/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp +++ b/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp @@ -53,7 +53,7 @@ */ vpRobotKinova::vpRobotKinova() : m_eMc(), m_plugin_location("./"), m_verbose(false), m_plugin_loaded(false), m_devices_count(0), - m_devices_list(NULL), m_active_device(-1), m_command_layer(CMD_LAYER_UNSET), m_command_layer_handle() + m_devices_list(nullptr), m_active_device(-1), m_command_layer(CMD_LAYER_UNSET), m_command_layer_handle() { init(); } @@ -761,10 +761,10 @@ void vpRobotKinova::loadPlugin() #endif // Verify that all functions has been loaded correctly - if ((KinovaCloseAPI == NULL) || (KinovaGetAngularCommand == NULL) || (KinovaGetAngularCommand == NULL) || - (KinovaGetCartesianCommand == NULL) || (KinovaGetDevices == NULL) || (KinovaInitAPI == NULL) || - (KinovaInitFingers == NULL) || (KinovaMoveHome == NULL) || (KinovaSendBasicTrajectory == NULL) || - (KinovaSetActiveDevice == NULL) || (KinovaSetAngularControl == NULL) || (KinovaSetCartesianControl == NULL)) { + if ((KinovaCloseAPI == nullptr) || (KinovaGetAngularCommand == nullptr) || (KinovaGetAngularCommand == nullptr) || + (KinovaGetCartesianCommand == nullptr) || (KinovaGetDevices == nullptr) || (KinovaInitAPI == nullptr) || + (KinovaInitFingers == nullptr) || (KinovaMoveHome == nullptr) || (KinovaSendBasicTrajectory == nullptr) || + (KinovaSetActiveDevice == nullptr) || (KinovaSetAngularControl == nullptr) || (KinovaSetCartesianControl == nullptr)) { throw(vpException(vpException::fatalError, "Cannot load plugin from \"%s\" folder", m_plugin_location.c_str())); } if (m_verbose) { diff --git a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp index cb6d242e6a..c94b8322ba 100644 --- a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp +++ b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp @@ -251,7 +251,7 @@ class vpRobotMavsdk::vpRobotMavsdkImpl bool isRunning() const { - if (m_system == NULL) { + if (m_system == nullptr) { return false; } else { diff --git a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp index 950c6e5b0c..64e5cd3b8f 100644 --- a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp +++ b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp @@ -813,7 +813,7 @@ bool vpRobotUniversalRobots::savePosFile(const std::string &filename, const vpCo FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "#UR - Joint position file\n" diff --git a/modules/robot/src/real-robot/viper/vpRobotViper650.cpp b/modules/robot/src/real-robot/viper/vpRobotViper650.cpp index b252cc2ed4..0955609b51 100644 --- a/modules/robot/src/real-robot/viper/vpRobotViper650.cpp +++ b/modules/robot/src/real-robot/viper/vpRobotViper650.cpp @@ -276,7 +276,7 @@ void vpRobotViper650::init(void) // Look if the power is on or off UInt32 HIPowerStatus; UInt32 EStopStatus; - Try(PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // Print the robot status @@ -660,7 +660,7 @@ vpRobotViper650::~vpRobotViper650(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // if (HIPowerStatus == 1) { @@ -772,7 +772,7 @@ void vpRobotViper650::powerOn(void) unsigned int nitermax = 10; for (unsigned int i = 0; i < nitermax; i++) { - Try(PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); if (EStopStatus == ESTOP_AUTO) { m_controlMode = AUTO; break; // exit for loop @@ -837,7 +837,7 @@ void vpRobotViper650::powerOff(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -871,7 +871,7 @@ bool vpRobotViper650::getPowerState(void) const bool status = false; // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -1731,14 +1731,14 @@ void vpRobotViper650::setVelocity(const vpRobot::vpControlFrameType frame, const if (TryStt < 0) { if (TryStt == VelStopOnJoint) { UInt32 axisInJoint[njoint]; - PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL); + PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr); for (unsigned int i = 0; i < njoint; i++) { if (axisInJoint[i]) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; } } else { printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt); - if (TryString != NULL) { + if (TryString != nullptr) { // The statement is in TryString, but we need to check the validity printf(" Error sentence %s\n", TryString); // Print the TryString } else { @@ -2162,7 +2162,7 @@ bool vpRobotViper650::savePosFile(const std::string &filename, const vpColVector FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "\ diff --git a/modules/robot/src/real-robot/viper/vpRobotViper850.cpp b/modules/robot/src/real-robot/viper/vpRobotViper850.cpp index c22d028a18..792279ee55 100644 --- a/modules/robot/src/real-robot/viper/vpRobotViper850.cpp +++ b/modules/robot/src/real-robot/viper/vpRobotViper850.cpp @@ -292,7 +292,7 @@ void vpRobotViper850::init(void) // Look if the power is on or off UInt32 HIPowerStatus; UInt32 EStopStatus; - Try(PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // Print the robot status @@ -680,7 +680,7 @@ vpRobotViper850::~vpRobotViper850(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); // if (HIPowerStatus == 1) { @@ -792,7 +792,7 @@ void vpRobotViper850::powerOn(void) unsigned int nitermax = 10; for (unsigned int i = 0; i < nitermax; i++) { - Try(PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); if (EStopStatus == ESTOP_AUTO) { m_controlMode = AUTO; break; // exit for loop @@ -857,7 +857,7 @@ void vpRobotViper850::powerOff(void) // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -891,7 +891,7 @@ bool vpRobotViper850::getPowerState(void) const bool status = false; // Look if the power is on or off UInt32 HIPowerStatus; - Try(PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus)); + Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus)); CAL_Wait(0.1); if (HIPowerStatus == 1) { @@ -1761,14 +1761,14 @@ void vpRobotViper850::setVelocity(const vpRobot::vpControlFrameType frame, const if (TryStt < 0) { if (TryStt == VelStopOnJoint) { UInt32 axisInJoint[njoint]; - PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL); + PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr); for (unsigned int i = 0; i < njoint; i++) { if (axisInJoint[i]) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; } } else { printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt); - if (TryString != NULL) { + if (TryString != nullptr) { // The statement is in TryString, but we need to check the validity printf(" Error sentence %s\n", TryString); // Print the TryString } else { @@ -2192,7 +2192,7 @@ bool vpRobotViper850::savePosFile(const std::string &filename, const vpColVector FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "\ diff --git a/modules/robot/src/real-robot/viper/vpViper650.cpp b/modules/robot/src/real-robot/viper/vpViper650.cpp index 704de86e7d..2531b8d986 100644 --- a/modules/robot/src/real-robot/viper/vpViper650.cpp +++ b/modules/robot/src/real-robot/viper/vpViper650.cpp @@ -46,7 +46,7 @@ #include #include -static const char *opt_viper650[] = {"CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", NULL}; +static const char *opt_viper650[] = {"CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr}; #ifdef VISP_HAVE_VIPER650_DATA const std::string vpViper650::CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME = @@ -438,7 +438,7 @@ void vpViper650::parseConfigFile(const std::string &filename) std::string key; ss >> key; - for (code = 0; NULL != opt_viper650[code]; ++code) { + for (code = 0; nullptr != opt_viper650[code]; ++code) { if (key.compare(opt_viper650[code]) == 0) { break; } diff --git a/modules/robot/src/real-robot/viper/vpViper850.cpp b/modules/robot/src/real-robot/viper/vpViper850.cpp index 53eac839cf..d5951a1714 100644 --- a/modules/robot/src/real-robot/viper/vpViper850.cpp +++ b/modules/robot/src/real-robot/viper/vpViper850.cpp @@ -46,7 +46,7 @@ #include #include -static const char *opt_viper850[] = {"CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", NULL}; +static const char *opt_viper850[] = {"CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr}; #ifdef VISP_HAVE_VIPER850_DATA const std::string vpViper850::CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME = @@ -439,7 +439,7 @@ void vpViper850::parseConfigFile(const std::string &filename) std::string key; ss >> key; - for (code = 0; NULL != opt_viper850[code]; ++code) { + for (code = 0; nullptr != opt_viper850[code]; ++code) { if (key.compare(opt_viper850[code]) == 0) { break; } diff --git a/modules/robot/src/robot-simulator/vpRobotCamera.cpp b/modules/robot/src/robot-simulator/vpRobotCamera.cpp index e5ac10c3d1..d9eecf8d4a 100644 --- a/modules/robot/src/robot-simulator/vpRobotCamera.cpp +++ b/modules/robot/src/robot-simulator/vpRobotCamera.cpp @@ -82,8 +82,8 @@ void vpRobotCamera::init() eJeAvailable = true; fJeAvailable = false; areJointLimitsAvailable = false; - qmin = NULL; - qmax = NULL; + qmin = nullptr; + qmax = nullptr; setMaxTranslationVelocity(1.); // vx, vy and vz max set to 1 m/s setMaxRotationVelocity(vpMath::rad(90)); // wx, wy and wz max set to 90 deg/s diff --git a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp index e64efb01a9..f45e033005 100644 --- a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp +++ b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp @@ -47,7 +47,7 @@ Basic constructor */ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator() - : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(NULL), size_fMi(8), fMi(NULL), + : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(nullptr), size_fMi(8), fMi(nullptr), artCoord(), artVel(), velocity(), #if defined(_WIN32) #elif defined(VISP_HAVE_PTHREAD) @@ -76,7 +76,7 @@ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator() \param do_display : When true, enables the display of the external view. */ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator(bool do_display) - : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(NULL), size_fMi(8), fMi(NULL), + : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(nullptr), size_fMi(8), fMi(nullptr), artCoord(), artVel(), velocity(), #if defined(_WIN32) #elif defined(VISP_HAVE_PTHREAD) diff --git a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp index d6c1d38888..ae1d7c870d 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp @@ -67,7 +67,7 @@ vpSimulatorAfma6::vpSimulatorAfma6() #if defined(_WIN32) DWORD dwThreadIdArray; - hThread = CreateThread(NULL, // default security attributes + hThread = CreateThread(nullptr, // default security attributes 0, // use default stack size launcher, // thread function name this, // argument to thread function @@ -77,7 +77,7 @@ vpSimulatorAfma6::vpSimulatorAfma6() pthread_attr_init(&attr); pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - pthread_create(&thread, NULL, launcher, (void *)this); + pthread_create(&thread, nullptr, launcher, (void *)this); #endif compute_fMi(); @@ -100,7 +100,7 @@ vpSimulatorAfma6::vpSimulatorAfma6(bool do_display) #if defined(_WIN32) DWORD dwThreadIdArray; - hThread = CreateThread(NULL, // default security attributes + hThread = CreateThread(nullptr, // default security attributes 0, // use default stack size launcher, // thread function name this, // argument to thread function @@ -110,7 +110,7 @@ vpSimulatorAfma6::vpSimulatorAfma6(bool do_display) pthread_attr_init(&attr); pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - pthread_create(&thread, NULL, launcher, (void *)this); + pthread_create(&thread, nullptr, launcher, (void *)this); #endif compute_fMi(); @@ -134,10 +134,10 @@ vpSimulatorAfma6::~vpSimulatorAfma6() CloseHandle(hThread); #elif defined(VISP_HAVE_PTHREAD) pthread_attr_destroy(&attr); - pthread_join(thread, NULL); + pthread_join(thread, nullptr); #endif - if (robotArms != NULL) { + if (robotArms != nullptr) { for (int i = 0; i < 6; i++) free_Bound_scene(&(robotArms[i])); } @@ -225,7 +225,7 @@ void vpSimulatorAfma6::init() */ void vpSimulatorAfma6::initDisplay() { - robotArms = NULL; + robotArms = nullptr; robotArms = new Bound_scene[6]; initArms(); setExternalCameraPosition(vpHomogeneousMatrix(0, 0, 0, 0, 0, vpMath::rad(180)) * @@ -276,7 +276,7 @@ void vpSimulatorAfma6::init(vpAfma6::vpAfma6ToolType tool, vpCameraParameters::v setCameraParameters(vpCameraParameters(1109.5735473989, 1112.1520168160, 320, 240)); - if (robotArms != NULL) { + if (robotArms != nullptr) { while (get_displayBusy()) vpTime::wait(2); free_Bound_scene(&(robotArms[5])); @@ -299,7 +299,7 @@ void vpSimulatorAfma6::init(vpAfma6::vpAfma6ToolType tool, vpCameraParameters::v setCameraParameters(vpCameraParameters(852.6583228197, 854.8084224761, 320, 240)); - if (robotArms != NULL) { + if (robotArms != nullptr) { while (get_displayBusy()) vpTime::wait(2); free_Bound_scene(&(robotArms[5])); @@ -322,7 +322,7 @@ void vpSimulatorAfma6::init(vpAfma6::vpAfma6ToolType tool, vpCameraParameters::v setCameraParameters(vpCameraParameters(853.4876600807, 856.0339170706, 320, 240)); - if (robotArms != NULL) { + if (robotArms != nullptr) { while (get_displayBusy()) vpTime::wait(2); free_Bound_scene(&(robotArms[5])); @@ -2027,7 +2027,7 @@ bool vpSimulatorAfma6::savePosFile(const std::string &filename, const vpColVecto { FILE *fd; fd = fopen(filename.c_str(), "w"); - if (fd == NULL) + if (fd == nullptr) return false; fprintf(fd, "\ @@ -2450,7 +2450,7 @@ bool vpSimulatorAfma6::setPosition(const vpHomogeneousMatrix &cdMo_, vpImage - // libdc1394-2.0.0-rc7 , d(NULL), - // list(NULL) + // libdc1394-2.0.0-rc7 , d(nullptr), + // list(nullptr) // #endif // { // throw vpException(vpException::functionNotImplementedError,"Not diff --git a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h index 4f06577a7a..48173e26dd 100644 --- a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h +++ b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h @@ -163,7 +163,7 @@ pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud); - sc.acquire(NULL, NULL, NULL, pointcloud); + sc.acquire(nullptr, nullptr, nullptr, pointcloud); pcl::visualization::PCLVisualizer::Ptr viewer (new pcl::visualization::PCLVisualizer ("3D Viewer")); pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud); @@ -172,7 +172,7 @@ viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0); while (true) { - sc.acquire(NULL, NULL, NULL, pointcloud); + sc.acquire(nullptr, nullptr, nullptr, pointcloud); static bool update = false; if (!update) { @@ -284,33 +284,33 @@ class VISP_EXPORT vpOccipitalStructure vpOccipitalStructure(); ~vpOccipitalStructure(); - void acquire(vpImage &gray, bool undistorted = false, double *ts = NULL); - void acquire(vpImage &rgb, bool undistorted = false, double *ts = NULL); + void acquire(vpImage &gray, bool undistorted = false, double *ts = nullptr); + void acquire(vpImage &rgb, bool undistorted = false, double *ts = nullptr); - void acquire(vpImage *rgb, vpImage *depth, vpColVector *acceleration_data = NULL, - vpColVector *gyroscope_data = NULL, bool undistorted = false, double *ts = NULL); - void acquire(vpImage *gray, vpImage *depth, vpColVector *acceleration_data = NULL, - vpColVector *gyroscope_data = NULL, bool undistorted = false, double *ts = NULL); + void acquire(vpImage *rgb, vpImage *depth, vpColVector *acceleration_data = nullptr, + vpColVector *gyroscope_data = nullptr, bool undistorted = false, double *ts = nullptr); + void acquire(vpImage *gray, vpImage *depth, vpColVector *acceleration_data = nullptr, + vpColVector *gyroscope_data = nullptr, bool undistorted = false, double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, - std::vector *const data_pointCloud = NULL, unsigned char *const data_infrared = NULL, - vpColVector *acceleration_data = NULL, vpColVector *gyroscope_data = NULL, bool undistorted = true, - double *ts = NULL); + std::vector *const data_pointCloud = nullptr, unsigned char *const data_infrared = nullptr, + vpColVector *acceleration_data = nullptr, vpColVector *gyroscope_data = nullptr, bool undistorted = true, + double *ts = nullptr); #ifdef VISP_HAVE_PCL void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, - unsigned char *const data_infrared = NULL, vpColVector *acceleration_data = NULL, - vpColVector *gyroscope_data = NULL, bool undistorted = true, double *ts = NULL); + unsigned char *const data_infrared = nullptr, vpColVector *acceleration_data = nullptr, + vpColVector *gyroscope_data = nullptr, bool undistorted = true, double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, - unsigned char *const data_infrared = NULL, vpColVector *acceleration_data = NULL, - vpColVector *gyroscope_data = NULL, bool undistorted = true, double *ts = NULL); + unsigned char *const data_infrared = nullptr, vpColVector *acceleration_data = nullptr, + vpColVector *gyroscope_data = nullptr, bool undistorted = true, double *ts = nullptr); #endif void getIMUVelocity(vpColVector *imu_vel, double *ts); void getIMUAcceleration(vpColVector *imu_acc, double *ts); - void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts = NULL); + void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts = nullptr); bool open(const ST::CaptureSessionSettings &settings); void close(); diff --git a/modules/sensor/include/visp3/sensor/vpPylonGrabber.h b/modules/sensor/include/visp3/sensor/vpPylonGrabber.h index 2842d9584c..726b7064ba 100644 --- a/modules/sensor/include/visp3/sensor/vpPylonGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpPylonGrabber.h @@ -165,7 +165,7 @@ class VISP_EXPORT vpPylonGrabber : public vpFrameGrabber */ virtual std::ostream &getCameraInfo(std::ostream &os) = 0; /*! - Return the handler to the active camera or NULL if the camera is not + Return the handler to the active camera or nullptr if the camera is not connected. This function was designed to provide a direct access to the Pylon SDK to get access to advanced functionalities that are not implemented in this class. diff --git a/modules/sensor/include/visp3/sensor/vpRealSense.h b/modules/sensor/include/visp3/sensor/vpRealSense.h index d64c5ed770..05975be0b9 100644 --- a/modules/sensor/include/visp3/sensor/vpRealSense.h +++ b/modules/sensor/include/visp3/sensor/vpRealSense.h @@ -212,7 +212,7 @@ rs.getIntrinsics(rs::stream::infrared).width); #endif while (1) { - rs.acquire((unsigned char *) Ic.bitmap, NULL, NULL, Ii.bitmap); + rs.acquire((unsigned char *) Ic.bitmap, nullptr, nullptr, Ii.bitmap); vpDisplay::display(Ic); vpDisplay::display(Ii); vpDisplay::flush(Ic); @@ -254,7 +254,7 @@ int main() { #endif while (1) { - rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, NULL, NULL, NULL, + rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, nullptr, nullptr, nullptr, rs::stream::color, rs::stream::depth_aligned_to_color); vpImageConvert::createDepthHistogram(Id_raw, Id); vpDisplay::display(Ic); @@ -358,7 +358,7 @@ class VISP_EXPORT vpRealSense void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, unsigned char *const data_infrared, - unsigned char *const data_infrared2 = NULL, const rs::stream &stream_color = rs::stream::color, + unsigned char *const data_infrared2 = nullptr, const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth, const rs::stream &stream_infrared = rs::stream::infrared, const rs::stream &stream_infrared2 = rs::stream::infrared2); @@ -372,13 +372,13 @@ class VISP_EXPORT vpRealSense void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, - unsigned char *const data_infrared, unsigned char *const data_infrared2 = NULL, + unsigned char *const data_infrared, unsigned char *const data_infrared2 = nullptr, const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth, const rs::stream &stream_infrared = rs::stream::infrared, const rs::stream &stream_infrared2 = rs::stream::infrared2); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, - unsigned char *const data_infrared, unsigned char *const data_infrared2 = NULL, + unsigned char *const data_infrared, unsigned char *const data_infrared2 = nullptr, const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth, const rs::stream &stream_infrared = rs::stream::infrared, const rs::stream &stream_infrared2 = rs::stream::infrared2); diff --git a/modules/sensor/include/visp3/sensor/vpRealSense2.h b/modules/sensor/include/visp3/sensor/vpRealSense2.h index 40f5c9c0f5..3e40c7ed14 100644 --- a/modules/sensor/include/visp3/sensor/vpRealSense2.h +++ b/modules/sensor/include/visp3/sensor/vpRealSense2.h @@ -146,7 +146,7 @@ pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud); - rs.acquire(NULL, NULL, NULL, pointcloud); + rs.acquire(nullptr, nullptr, nullptr, pointcloud); pcl::visualization::PCLVisualizer::Ptr viewer (new pcl::visualization::PCLVisualizer ("3D Viewer")); pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud); @@ -155,7 +155,7 @@ viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0); while (true) { - rs.acquire(NULL, NULL, NULL, pointcloud); + rs.acquire(nullptr, nullptr, nullptr, pointcloud); static bool update = false; if (!update) { @@ -202,7 +202,7 @@ #endif while (true) { - rs.acquire((unsigned char *) Ic.bitmap, NULL, NULL, Ii.bitmap); + rs.acquire((unsigned char *) Ic.bitmap, nullptr, nullptr, Ii.bitmap); vpDisplay::display(Ic); vpDisplay::display(Ii); vpDisplay::flush(Ic); @@ -243,7 +243,7 @@ rs2::align align_to(RS2_STREAM_COLOR); while (true) { - rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, NULL, NULL, &align_to); + rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, nullptr, nullptr, &align_to); vpImageConvert::createDepthHistogram(Id_raw, Id); vpDisplay::display(Ic); vpDisplay::display(Id); @@ -290,39 +290,39 @@ class VISP_EXPORT vpRealSense2 vpRealSense2(); virtual ~vpRealSense2(); - void acquire(vpImage &grey, double *ts = NULL); - void acquire(vpImage &color, double *ts = NULL); + void acquire(vpImage &grey, double *ts = nullptr); + void acquire(vpImage &color, double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, unsigned char *const data_infrared, - rs2::align *const align_to = NULL, double *ts = NULL); + rs2::align *const align_to = nullptr, double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, unsigned char *const data_infrared1, - unsigned char *const data_infrared2, rs2::align *const align_to, double *ts = NULL); + unsigned char *const data_infrared2, rs2::align *const align_to, double *ts = nullptr); #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) - void acquire(vpImage *left, vpImage *right, double *ts = NULL); + void acquire(vpImage *left, vpImage *right, double *ts = nullptr); void acquire(vpImage *left, vpImage *right, vpHomogeneousMatrix *cMw, - vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence = NULL, double *ts = NULL); + vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence = nullptr, double *ts = nullptr); void acquire(vpImage *left, vpImage *right, vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, vpColVector *imu_vel, vpColVector *imu_acc, - unsigned int *tracker_confidence = NULL, double *ts = NULL); + unsigned int *tracker_confidence = nullptr, double *ts = nullptr); #endif #ifdef VISP_HAVE_PCL void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, - unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL, double *ts = NULL); + unsigned char *const data_infrared = nullptr, rs2::align *const align_to = nullptr, double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, - double *ts = NULL); + double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, - unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL, double *ts = NULL); + unsigned char *const data_infrared = nullptr, rs2::align *const align_to = nullptr, double *ts = nullptr); void acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, - double *ts = NULL); + double *ts = nullptr); #endif void close(); @@ -352,7 +352,7 @@ class VISP_EXPORT vpRealSense2 inline float getMaxZ() const { return m_max_Z; } #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) - unsigned int getOdometryData(vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, double *ts = NULL); + unsigned int getOdometryData(vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, double *ts = nullptr); #endif //! Get a reference to `rs2::pipeline`. diff --git a/modules/sensor/include/visp3/sensor/vpSickLDMRS.h b/modules/sensor/include/visp3/sensor/vpSickLDMRS.h index de42458366..650e6aec4d 100644 --- a/modules/sensor/include/visp3/sensor/vpSickLDMRS.h +++ b/modules/sensor/include/visp3/sensor/vpSickLDMRS.h @@ -116,7 +116,7 @@ class VISP_EXPORT vpSickLDMRS : public vpLaserScanner /*! Copy constructor. */ vpSickLDMRS(const vpSickLDMRS &sick) - : vpLaserScanner(sick), socket_fd(-1), body(NULL), vAngle(), time_offset(0), isFirstMeasure(true), + : vpLaserScanner(sick), socket_fd(-1), body(nullptr), vAngle(), time_offset(0), isFirstMeasure(true), maxlen_body(104000) { *this = sick; diff --git a/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h b/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h index 30e1870bec..2a0370c23b 100644 --- a/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h @@ -86,8 +86,8 @@ class VISP_EXPORT vpUeyeGrabber vpUeyeGrabber(); virtual ~vpUeyeGrabber(); - void acquire(vpImage &I, double *timestamp_camera = NULL, std::string *timestamp_system = NULL); - void acquire(vpImage &I, double *timestamp_camera = NULL, std::string *timestamp_system = NULL); + void acquire(vpImage &I, double *timestamp_camera = nullptr, std::string *timestamp_system = nullptr); + void acquire(vpImage &I, double *timestamp_camera = nullptr, std::string *timestamp_system = nullptr); std::string getActiveCameraModel() const; std::string getActiveCameraSerialNumber() const; diff --git a/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h b/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h index 0a5ace7663..9e02200464 100644 --- a/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h +++ b/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h @@ -188,9 +188,9 @@ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpV4l2Grabber(const vpV4l2Grabber &) - // : fd(-1), device(), cap(), streamparm(), inp(NULL), std(NULL), - // fmt(NULL), ctl(NULL), - // fmt_v4l2(), fmt_me(), reqbufs(), buf_v4l2(NULL), buf_me(NULL), + // : fd(-1), device(), cap(), streamparm(), inp(nullptr), std(nullptr), + // fmt(nullptr), ctl(nullptr), + // fmt_v4l2(), fmt_me(), reqbufs(), buf_v4l2(nullptr), buf_me(nullptr), // queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), // m_nbuffers(3), field(0), streaming(false), // m_input(vpV4l2Grabber::DEFAULT_INPUT), diff --git a/modules/sensor/src/force-torque/vpComedi.cpp b/modules/sensor/src/force-torque/vpComedi.cpp index b52ae080fd..c4bee5e8a3 100644 --- a/modules/sensor/src/force-torque/vpComedi.cpp +++ b/modules/sensor/src/force-torque/vpComedi.cpp @@ -46,7 +46,7 @@ Default constructor. */ vpComedi::vpComedi() - : m_device("/dev/comedi0"), m_handler(NULL), m_subdevice(0), m_range(0), m_aref(AREF_DIFF), m_nchannel(6), + : m_device("/dev/comedi0"), m_handler(nullptr), m_subdevice(0), m_range(0), m_aref(AREF_DIFF), m_nchannel(6), m_range_info(6), m_maxdata(6), m_chanlist(6) { } @@ -91,7 +91,7 @@ void vpComedi::close() { if (m_handler) { comedi_close(m_handler); - m_handler = NULL; + m_handler = nullptr; } } @@ -104,7 +104,7 @@ void vpComedi::close() */ std::vector vpComedi::getRawData() const { - if (m_handler == NULL) { + if (m_handler == nullptr) { throw vpException(vpException::fatalError, "Comedi device not open"); } // Get raw data @@ -132,7 +132,7 @@ std::vector vpComedi::getRawData() const */ vpColVector vpComedi::getPhyData() const { - if (m_handler == NULL) { + if (m_handler == nullptr) { throw vpException(vpException::fatalError, "Comedi device not open"); } // Get raw data @@ -154,7 +154,7 @@ vpColVector vpComedi::getPhyData() const //! getPhyDataAsync(). std::string vpComedi::getPhyDataUnits() const { - if (m_handler == NULL) { + if (m_handler == nullptr) { throw vpException(vpException::fatalError, "Comedi device not open"); } std::string units; diff --git a/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp b/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp index bd5cc76534..b65ca6e197 100644 --- a/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp +++ b/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp @@ -42,7 +42,7 @@ #include #include -static Calibration *s_calibinfo = NULL; //!< Struct containing calibration information +static Calibration *s_calibinfo = nullptr; //!< Struct containing calibration information /*! * Default constructor. @@ -120,10 +120,10 @@ void vpForceTorqueAtiSensor::unbias() */ void vpForceTorqueAtiSensor::close() { - if (s_calibinfo != NULL) { + if (s_calibinfo != nullptr) { // free memory allocated to calibration structure destroyCalibration(s_calibinfo); - s_calibinfo = NULL; + s_calibinfo = nullptr; } vpComedi::close(); } @@ -202,7 +202,7 @@ void vpForceTorqueAtiSensor::setCalibrationFile(const std::string &calibfile, un // Create calibration struct s_calibinfo = createCalibration(m_calibfile.c_str(), m_index); - if (s_calibinfo == NULL) { + if (s_calibinfo == nullptr) { throw vpException(vpException::fatalError, "Calibration file %s couldn't be loaded", m_calibfile.c_str()); } @@ -231,7 +231,7 @@ int main() */ std::ostream &operator<<(std::ostream &os, const vpForceTorqueAtiSensor &ati) { - if (s_calibinfo == NULL) { + if (s_calibinfo == nullptr) { os << "Calibration Information is not available" << std::endl; return os; } diff --git a/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp b/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp index f6aec9b132..a2364259b1 100644 --- a/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp +++ b/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp @@ -69,7 +69,7 @@ vp1394CMUGrabber::~vp1394CMUGrabber() // delete camera instance if (camera) { delete camera; - camera = NULL; + camera = nullptr; } } @@ -206,7 +206,7 @@ void vp1394CMUGrabber::acquire(vpImage &I) { // get image data unsigned long length; - unsigned char *rawdata = NULL; + unsigned char *rawdata = nullptr; int dropped; unsigned int size; @@ -268,7 +268,7 @@ void vp1394CMUGrabber::acquire(vpImage &I) { // get image data unsigned long length; - unsigned char *rawdata = NULL; + unsigned char *rawdata = nullptr; int dropped; unsigned int size; diff --git a/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp b/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp index 512e4fa2ab..9f1cab44b0 100644 --- a/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp +++ b/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp @@ -118,12 +118,12 @@ int main() */ vp1394TwoGrabber::vp1394TwoGrabber(bool reset) - : camera(NULL), cameras(NULL), num_cameras(0), camera_id(0), verbose(false), camIsOpen(NULL), + : camera(nullptr), cameras(nullptr), num_cameras(0), camera_id(0), verbose(false), camIsOpen(nullptr), num_buffers(4), // ring buffer size - isDataModified(NULL), initialShutterMode(NULL), dataCam(NULL) + isDataModified(nullptr), initialShutterMode(nullptr), dataCam(nullptr) #ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > libdc1394-2.0.0-rc7 , - d(NULL), list(NULL) + d(nullptr), list(nullptr) #endif { // protected members @@ -1289,7 +1289,7 @@ void vp1394TwoGrabber::initialize(bool reset) if (init == false) { // Find cameras #ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > libdc1394-2.0.0-rc7 - if (d != NULL) + if (d != nullptr) dc1394_free(d); d = dc1394_new(); @@ -1307,7 +1307,7 @@ void vp1394TwoGrabber::initialize(bool reset) throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "No cameras found")); } - if (cameras != NULL) + if (cameras != nullptr) delete[] cameras; cameras = new dc1394camera_t *[list->num]; @@ -1331,14 +1331,14 @@ void vp1394TwoGrabber::initialize(bool reset) dc1394_reset_bus(cameras[0]); } - // if (list != NULL) + // if (list != nullptr) dc1394_camera_free_list(list); - list = NULL; + list = nullptr; #elif defined VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 - if (cameras != NULL) + if (cameras != nullptr) free(cameras); - cameras = NULL; + cameras = nullptr; int err = dc1394_find_cameras(&cameras, &num_cameras); if (err != DC1394_SUCCESS && err != DC1394_NO_CAMERA) { @@ -1379,7 +1379,7 @@ void vp1394TwoGrabber::initialize(bool reset) std::cout << "-----------------------------" << std::endl; } - if (camIsOpen != NULL) + if (camIsOpen != nullptr) delete[] camIsOpen; camIsOpen = new bool[num_cameras]; for (unsigned int i = 0; i < num_cameras; i++) { @@ -1486,43 +1486,43 @@ void vp1394TwoGrabber::close() #endif } } - if (camIsOpen != NULL) { + if (camIsOpen != nullptr) { delete[] camIsOpen; - camIsOpen = NULL; + camIsOpen = nullptr; } #ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > libdc1394-2.0.0-rc7 - if (cameras != NULL) { + if (cameras != nullptr) { delete[] cameras; - cameras = NULL; + cameras = nullptr; } - if (d != NULL) { + if (d != nullptr) { dc1394_free(d); - d = NULL; + d = nullptr; } #elif defined VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 - if (cameras != NULL) { + if (cameras != nullptr) { free(cameras); - cameras = NULL; + cameras = nullptr; } #endif - camIsOpen = NULL; + camIsOpen = nullptr; num_cameras = 0; // remove data for the parameters - if (isDataModified != NULL) { + if (isDataModified != nullptr) { delete[] isDataModified; - isDataModified = NULL; + isDataModified = nullptr; } - if (initialShutterMode != NULL) { + if (initialShutterMode != nullptr) { delete[] initialShutterMode; - initialShutterMode = NULL; + initialShutterMode = nullptr; } - if (dataCam != NULL) { + if (dataCam != nullptr) { delete[] dataCam; - dataCam = NULL; + dataCam = nullptr; } init = false; @@ -2120,7 +2120,7 @@ dc1394video_frame_t *vp1394TwoGrabber::dequeue() throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "No camera found")); } - dc1394video_frame_t *frame = NULL; + dc1394video_frame_t *frame = nullptr; if (dc1394_capture_dequeue(camera, DC1394_CAPTURE_POLICY_WAIT, &frame) != DC1394_SUCCESS) { vpERROR_TRACE("Error: Failed to capture from camera %d\n", camera_id); @@ -2983,10 +2983,10 @@ void vp1394TwoGrabber::resetBus() dc1394_camera_free(camera); dc1394_free(d); - d = NULL; - // if (cameras != NULL) + d = nullptr; + // if (cameras != nullptr) delete[] cameras; - cameras = NULL; + cameras = nullptr; #elif defined VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 setCamera(camera_id); @@ -2996,15 +2996,15 @@ void vp1394TwoGrabber::resetBus() dc1394_free_camera(cameras[i]); } free(cameras); - cameras = NULL; + cameras = nullptr; dc1394_reset_bus(camera); dc1394_free_camera(camera); #endif - if (camIsOpen != NULL) + if (camIsOpen != nullptr) delete[] camIsOpen; - camIsOpen = NULL; + camIsOpen = nullptr; num_cameras = 0; diff --git a/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp b/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp index 1657dd1695..a1603b4244 100644 --- a/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp +++ b/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp @@ -40,7 +40,7 @@ #include -vpDirectShowDevice *vpDirectShowGrabberImpl::deviceList = NULL; +vpDirectShowDevice *vpDirectShowGrabberImpl::deviceList = nullptr; unsigned int vpDirectShowGrabberImpl::nbDevices; /*! @@ -68,7 +68,7 @@ vpDirectShowGrabberImpl::vpDirectShowGrabberImpl() init = false; initCo = false; // COM initialization - if (FAILED(hr = CoInitializeEx(NULL, COINIT_MULTITHREADED))) { + if (FAILED(hr = CoInitializeEx(nullptr, COINIT_MULTITHREADED))) { std::string err; HRtoStr(err); throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Can't initialize COM\n" + err)); @@ -76,8 +76,8 @@ vpDirectShowGrabberImpl::vpDirectShowGrabberImpl() initCo = true; // create the device list - if (deviceList == NULL) { - CComPtr pVideoInputEnum = NULL; + if (deviceList == nullptr) { + CComPtr pVideoInputEnum = nullptr; if (enumerate(pVideoInputEnum)) { createDeviceList(pVideoInputEnum); @@ -94,8 +94,8 @@ vpDirectShowGrabberImpl::vpDirectShowGrabberImpl() void vpDirectShowGrabberImpl::open() { // create the device list - if (deviceList == NULL) { - CComPtr pVideoInputEnum = NULL; + if (deviceList == nullptr) { + CComPtr pVideoInputEnum = nullptr; if (enumerate(pVideoInputEnum)) { createDeviceList(pVideoInputEnum); @@ -168,7 +168,7 @@ bool vpDirectShowGrabberImpl::initDirectShow() pGraph->QueryInterface(IID_IMediaControl, reinterpret_cast(&pControl)); pGraph->QueryInterface(IID_IMediaEvent, (void **)&pEvent); - pMediaFilter->SetSyncSource(NULL); + pMediaFilter->SetSyncSource(nullptr); pMediaFilter.Release(); return true; @@ -186,11 +186,11 @@ vpDirectShowGrabberImpl::~vpDirectShowGrabberImpl() { close(); } */ bool vpDirectShowGrabberImpl::enumerate(CComPtr &ppVideoInputEnum) { - CComPtr pDevEnum = NULL; + CComPtr pDevEnum = nullptr; bool res = false; // Enumerate system devices - hr = pDevEnum.CoCreateInstance(CLSID_SystemDeviceEnum, NULL, CLSCTX_INPROC_SERVER); + hr = pDevEnum.CoCreateInstance(CLSID_SystemDeviceEnum, nullptr, CLSCTX_INPROC_SERVER); // if it is a success if (SUCCEEDED(hr)) { @@ -272,15 +272,15 @@ bool vpDirectShowGrabberImpl::getDevice(unsigned int n, CComPtr &pp return false; // if we can't enumerate the devices, quit - CComPtr pVideoInputEnum = NULL; + CComPtr pVideoInputEnum = nullptr; if (!enumerate(pVideoInputEnum)) return false; - CComPtr pMoniker = NULL; + CComPtr pMoniker = nullptr; bool deviceFound = false; // Enumerates the different inputs - while (pVideoInputEnum->Next(1, &pMoniker, NULL) == S_OK && !deviceFound) { + while (pVideoInputEnum->Next(1, &pMoniker, nullptr) == S_OK && !deviceFound) { // implicit conversion should work ... if (deviceList[n] == vpDirectShowDevice(pMoniker)) { // we get the filter @@ -358,7 +358,7 @@ bool vpDirectShowGrabberImpl::createGraph() bool vpDirectShowGrabberImpl::createSampleGrabber(CComPtr &ppGrabberFilter) { // Creates the sample grabber - hr = ppGrabberFilter.CoCreateInstance(CLSID_SampleGrabber, NULL, CLSCTX_INPROC_SERVER); + hr = ppGrabberFilter.CoCreateInstance(CLSID_SampleGrabber, nullptr, CLSCTX_INPROC_SERVER); if (FAILED(hr)) return false; @@ -376,7 +376,7 @@ bool vpDirectShowGrabberImpl::createSampleGrabber(CComPtr &ppGrabbe mt.majortype = MEDIATYPE_Video; // ask for a connection - mt.subtype = MEDIATYPE_NULL; + mt.subtype = MEDIATYPE_nullptr; if (FAILED(hr = pGrabberI->SetMediaType(&mt))) return false; @@ -482,12 +482,12 @@ bool vpDirectShowGrabberImpl::connectSourceToGrabber(CComPtr &_pCap /* //get the capture source's output pin CComPtr pCapSourcePin; - if(FAILED(pBuild->FindPin(_pCapSource, PINDIR_OUTPUT, NULL, NULL, false, 0, + if(FAILED(pBuild->FindPin(_pCapSource, PINDIR_OUTPUT, nullptr, nullptr, false, 0, &pCapSourcePin))) return false; //get the grabber's input pin CComPtr pGrabberInputPin; - if(FAILED(pBuild->FindPin(_pGrabberFilter, PINDIR_INPUT, NULL, NULL, false, + if(FAILED(pBuild->FindPin(_pGrabberFilter, PINDIR_INPUT, nullptr, nullptr, false, 0, &pGrabberInputPin))) return false; //connect the two of them @@ -497,21 +497,21 @@ bool vpDirectShowGrabberImpl::connectSourceToGrabber(CComPtr &_pCap //not used anymore, we can release it pGrabberInputPin.Release(); */ - if (FAILED(hr = pBuild->RenderStream(NULL, NULL, _pCapSource, NULL, _pGrabberFilter))) + if (FAILED(hr = pBuild->RenderStream(nullptr, nullptr, _pCapSource, nullptr, _pGrabberFilter))) return false; // get the Null renderer - CComPtr pNull = NULL; - if (FAILED(pNull.CoCreateInstance(CLSID_NullRenderer, NULL, CLSCTX_INPROC_SERVER))) + CComPtr pNull = nullptr; + if (FAILED(pNull.CoCreateInstance(CLSID_NullRenderer, nullptr, CLSCTX_INPROC_SERVER))) return false; if (FAILED(pGraph->AddFilter(pNull, L"NullRenderer")) || - FAILED(pBuild->RenderStream(NULL, NULL, _pGrabberFilter, NULL, pNull))) + FAILED(pBuild->RenderStream(nullptr, nullptr, _pGrabberFilter, nullptr, pNull))) return false; // get the capture source's output pin CComPtr pCapSourcePin; - if (FAILED(pBuild->FindPin(_pCapSource, PINDIR_OUTPUT, NULL, NULL, false, 0, &pCapSourcePin))) + if (FAILED(pBuild->FindPin(_pCapSource, PINDIR_OUTPUT, nullptr, nullptr, false, 0, &pCapSourcePin))) return false; // checks the media type of the capture filter // and if the image needs to be inverted @@ -532,7 +532,7 @@ bool vpDirectShowGrabberImpl::connectSourceToGrabber(CComPtr &_pCap */ bool vpDirectShowGrabberImpl::removeAll() { - CComPtr pEnum = NULL; + CComPtr pEnum = nullptr; CComPtr pFilter; ULONG cFetched; @@ -684,7 +684,7 @@ bool vpDirectShowGrabberImpl::setDevice(unsigned int id) */ void vpDirectShowGrabberImpl::displayDevices() { - if (deviceList == NULL) { + if (deviceList == nullptr) { throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Initialization not done")); } @@ -721,7 +721,7 @@ bool vpDirectShowGrabberImpl::setImageSize(unsigned int width, unsigned int heig throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Initialization not done")); } - return setFormat(width, height, NULL); + return setFormat(width, height, nullptr); } /*! @@ -750,7 +750,7 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, bool found = false; // gets the stream config interface - IAMStreamConfig *pConfig = NULL; + IAMStreamConfig *pConfig = nullptr; if (FAILED(hr = pBuild->FindInterface(&LOOK_UPSTREAM_ONLY, // Capture pin. / Preview pin 0, // Any media type. @@ -759,7 +759,7 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, return false; // gets the video control interface - IAMVideoControl *pVideoControl = NULL; + IAMVideoControl *pVideoControl = nullptr; if (FAILED(hr = pBuild->FindInterface(&LOOK_UPSTREAM_ONLY, // Capture pin. / Preview pin 0, // Any media type. @@ -769,7 +769,7 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, // get the grabber's input pin CComPtr pCapSourcePin; - if (FAILED(pBuild->FindPin(pCapSource, PINDIR_OUTPUT, NULL, NULL, false, 0, &pCapSourcePin))) + if (FAILED(pBuild->FindPin(pCapSource, PINDIR_OUTPUT, nullptr, nullptr, false, 0, &pCapSourcePin))) return false; int iCount = 0, iSize = 0; @@ -790,12 +790,12 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, if ((pmtConfig->majortype == sgCB.connectedMediaType.majortype) && (pmtConfig->subtype == sgCB.connectedMediaType.subtype) && (pmtConfig->formattype == sgCB.connectedMediaType.formattype) && - (pmtConfig->cbFormat >= sizeof(VIDEOINFOHEADER)) && (pmtConfig->pbFormat != NULL)) { + (pmtConfig->cbFormat >= sizeof(VIDEOINFOHEADER)) && (pmtConfig->pbFormat != nullptr)) { VIDEOINFOHEADER *pVih = (VIDEOINFOHEADER *)pmtConfig->pbFormat; LONG lWidth = pVih->bmiHeader.biWidth; LONG lHeight = pVih->bmiHeader.biHeight; - if (framerate != NULL) { + if (framerate != nullptr) { if ((unsigned int)lWidth == width && (unsigned int)lHeight == height) { pVih->AvgTimePerFrame = (LONGLONG)(10000000 / framerate); @@ -845,7 +845,7 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, } } if (!found) - if (framerate != NULL) + if (framerate != nullptr) std::cout << "The " << width << " x " << height << " at " << framerate << " fps source image format is not available. " << std::endl << std::endl; @@ -883,7 +883,7 @@ bool vpDirectShowGrabberImpl::getStreamCapabilities() } // gets the stream config interface - IAMStreamConfig *pConfig = NULL; + IAMStreamConfig *pConfig = nullptr; if (FAILED(hr = pBuild->FindInterface(&LOOK_UPSTREAM_ONLY, // Capture pin. / Preview pin 0, // Any media type. @@ -988,7 +988,7 @@ bool vpDirectShowGrabberImpl::setMediaType(int mediaTypeID) } // gets the stream config interface - IAMStreamConfig *pConfig = NULL; + IAMStreamConfig *pConfig = nullptr; if (FAILED(hr = pBuild->FindInterface(&LOOK_UPSTREAM_ONLY, // Capture pin. / Preview pin 0, // Any media type. @@ -1030,7 +1030,7 @@ int vpDirectShowGrabberImpl::getMediaType() VIDEOINFOHEADER *pVihConnected = (VIDEOINFOHEADER *)sgCB.connectedMediaType.pbFormat; // gets the stream config interface - IAMStreamConfig *pConfig = NULL; + IAMStreamConfig *pConfig = nullptr; if (FAILED(hr = pBuild->FindInterface(&LOOK_UPSTREAM_ONLY, // Capture pin. / Preview pin 0, // Any media type. @@ -1055,7 +1055,7 @@ int vpDirectShowGrabberImpl::getMediaType() if ((pmtConfig->majortype == sgCB.connectedMediaType.majortype) && (pmtConfig->subtype == sgCB.connectedMediaType.subtype) && (pmtConfig->formattype == sgCB.connectedMediaType.formattype) && - (pmtConfig->cbFormat >= sizeof(VIDEOINFOHEADER)) && (pmtConfig->pbFormat != NULL)) { + (pmtConfig->cbFormat >= sizeof(VIDEOINFOHEADER)) && (pmtConfig->pbFormat != nullptr)) { VIDEOINFOHEADER *pVih = (VIDEOINFOHEADER *)pmtConfig->pbFormat; if (pVih->bmiHeader.biWidth == pVihConnected->bmiHeader.biWidth && pVih->bmiHeader.biHeight == pVihConnected->bmiHeader.biHeight) @@ -1075,7 +1075,7 @@ int vpDirectShowGrabberImpl::getMediaType() */ void vpDirectShowGrabberImpl::MyDeleteMediaType(AM_MEDIA_TYPE *pmt) { - if (pmt != NULL) { + if (pmt != nullptr) { MyFreeMediaType(*pmt); // See FreeMediaType for the implementation. CoTaskMemFree(pmt); } @@ -1089,12 +1089,12 @@ void vpDirectShowGrabberImpl::MyFreeMediaType(AM_MEDIA_TYPE &mt) if (mt.cbFormat != 0) { CoTaskMemFree((PVOID)mt.pbFormat); mt.cbFormat = 0; - mt.pbFormat = NULL; + mt.pbFormat = nullptr; } - if (mt.pUnk != NULL) { + if (mt.pUnk != nullptr) { // Unecessary because pUnk should not be used, but safest. mt.pUnk->Release(); - mt.pUnk = NULL; + mt.pUnk = nullptr; } } diff --git a/modules/sensor/src/framegrabber/directshow/vpDirectShowSampleGrabberI.cpp b/modules/sensor/src/framegrabber/directshow/vpDirectShowSampleGrabberI.cpp index 6d6e89a78b..0307a84319 100644 --- a/modules/sensor/src/framegrabber/directshow/vpDirectShowSampleGrabberI.cpp +++ b/modules/sensor/src/framegrabber/directshow/vpDirectShowSampleGrabberI.cpp @@ -51,7 +51,7 @@ vpDirectShowSampleGrabberI::vpDirectShowSampleGrabberI() : acqGrayDemand(false), acqRGBaDemand(false), specialMediaType(false), invertedSource(false) { // semaphore(0), max value = 1 - copySem = CreateSemaphore(NULL, 0, 1, NULL); + copySem = CreateSemaphore(nullptr, 0, 1, nullptr); } /*! @@ -65,7 +65,7 @@ vpDirectShowSampleGrabberI::~vpDirectShowSampleGrabberI() STDMETHODIMP vpDirectShowSampleGrabberI::QueryInterface(REFIID riid, void **ppvObject) { - if (NULL == ppvObject) + if (nullptr == ppvObject) return E_POINTER; if (riid == __uuidof(IUnknown)) { *ppvObject = static_cast(this); @@ -270,7 +270,7 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo } // increment the semaphore - allows acquire to continue execution - ReleaseSemaphore(copySem, 1, NULL); + ReleaseSemaphore(copySem, 1, nullptr); } return S_OK; } diff --git a/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp b/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp index 69f442832c..a982ee310c 100644 --- a/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp +++ b/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp @@ -100,7 +100,7 @@ std::ostream &vpFlyCaptureGrabber::getCameraInfo(std::ostream &os) } /*! - Return the handler to the active camera or NULL if the camera is not + Return the handler to the active camera or nullptr if the camera is not connected. This function was designed to provide a direct access to the FlyCapture SDK to get access to advanced functionalities that are not implemented in this class. @@ -185,7 +185,7 @@ FlyCapture2::Camera *vpFlyCaptureGrabber::getCameraHandler() if (m_connected == true) { return &m_camera; } else { - return NULL; + return nullptr; } } diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp b/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp index d08d237f46..68320a1fe5 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp +++ b/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp @@ -64,7 +64,7 @@ vpPylonFactory &vpPylonFactory::instance() \param dev_class The device class. See vpPylonFactory::DeviceClass for valid values. \return The pointer towards the vpPylonGrabber object. It's the - caller's responsibility to destroy the object. NULL pointer will be + caller's responsibility to destroy the object. nullptr pointer will be returned if requested object can't be properly created. */ vpPylonGrabber *vpPylonFactory::createPylonGrabber(DeviceClass dev_class) @@ -77,7 +77,7 @@ vpPylonGrabber *vpPylonFactory::createPylonGrabber(DeviceClass dev_class) return new vpPylonGrabberUsb(); break; default: - return NULL; + return nullptr; break; } } diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp index 126ce0bf12..88217022fe 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp +++ b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp @@ -105,7 +105,7 @@ std::ostream &vpPylonGrabberGigE::getCameraInfo(std::ostream &os) } /*! - Return the handler to the active camera or NULL if the camera is not + Return the handler to the active camera or nullptr if the camera is not connected. This function was designed to provide a direct access to the Pylon SDK to get access to advanced functionalities that are not implemented in this class. @@ -117,7 +117,7 @@ Pylon::CInstantCamera *vpPylonGrabberGigE::getCameraHandler() if (m_connected == true) { return &m_camera; } else { - return NULL; + return nullptr; } } diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp index 74ca4c0377..114d1780d2 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp +++ b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp @@ -105,7 +105,7 @@ std::ostream &vpPylonGrabberUsb::getCameraInfo(std::ostream &os) } /*! - Return the handler to the active camera or NULL if the camera is not + Return the handler to the active camera or nullptr if the camera is not connected. This function was designed to provide a direct access to the Pylon SDK to get access to advanced functionalities that are not implemented in this class. @@ -117,7 +117,7 @@ Pylon::CInstantCamera *vpPylonGrabberUsb::getCameraHandler() if (m_connected == true) { return &m_camera; } else { - return NULL; + return nullptr; } } diff --git a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp index b0c0b64034..b90ac24d7b 100644 --- a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp +++ b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp @@ -95,7 +95,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl { public: vpUeyeGrabberImpl() - : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(NULL), m_cameraList(NULL), m_bLive(true), + : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(nullptr), m_cameraList(nullptr), m_bLive(true), m_bLiveStarted(false), m_verbose(false), m_I_temp() { ZeroMemory(&m_SensorInfo, sizeof(SENSORINFO)); @@ -140,7 +140,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (ret == IS_SUCCESS) { INT dummy = 0; - char *pLast = NULL, *pMem = NULL; + char *pLast = nullptr, *pMem = nullptr; is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast); m_pLastBuffer = pLast; @@ -149,14 +149,14 @@ class vpUeyeGrabber::vpUeyeGrabberImpl return; int nNum = getImageNum(m_pLastBuffer); - if (timestamp_camera != NULL || timestamp_system != NULL) { + if (timestamp_camera != nullptr || timestamp_system != nullptr) { int nImageID = getImageID(m_pLastBuffer); UEYEIMAGEINFO ImageInfo; if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo, sizeof(ImageInfo)) == IS_SUCCESS) { - if (timestamp_camera != NULL) { + if (timestamp_camera != nullptr) { *timestamp_camera = static_cast(ImageInfo.u64TimestampDevice) / 10000.; } - if (timestamp_system != NULL) { + if (timestamp_system != nullptr) { std::stringstream ss; ss << ImageInfo.TimestampSystem.wYear << ":" << std::setfill('0') << std::setw(2) << ImageInfo.TimestampSystem.wMonth << ":" << std::setfill('0') << std::setw(2) @@ -243,7 +243,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (ret == IS_SUCCESS) { INT dummy = 0; - char *pLast = NULL, *pMem = NULL; + char *pLast = nullptr, *pMem = nullptr; is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast); m_pLastBuffer = pLast; @@ -252,14 +252,14 @@ class vpUeyeGrabber::vpUeyeGrabberImpl return; int nNum = getImageNum(m_pLastBuffer); - if (timestamp_camera != NULL || timestamp_system != NULL) { + if (timestamp_camera != nullptr || timestamp_system != nullptr) { int nImageID = getImageID(m_pLastBuffer); UEYEIMAGEINFO ImageInfo; if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo, sizeof(ImageInfo)) == IS_SUCCESS) { - if (timestamp_camera != NULL) { + if (timestamp_camera != nullptr) { *timestamp_camera = static_cast(ImageInfo.u64TimestampDevice) / 10000.; } - if (timestamp_system != NULL) { + if (timestamp_system != nullptr) { std::stringstream ss; ss << ImageInfo.TimestampSystem.wYear << ":" << std::setfill('0') << std::setw(2) << ImageInfo.TimestampSystem.wMonth << ":" << std::setfill('0') << std::setw(2) @@ -321,7 +321,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl bool allocImages() { - m_pLastBuffer = NULL; + m_pLastBuffer = nullptr; int nWidth = 0; int nHeight = 0; @@ -424,7 +424,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl enableEvent(IS_SET_EVENT_FRAME); } - m_pLastBuffer = NULL; + m_pLastBuffer = nullptr; return ret; } @@ -471,8 +471,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl int ret = 0; m_event = event; #ifndef __linux__ - m_hEvent = CreateEvent(NULL, FALSE, FALSE, NULL); - if (m_hEvent == NULL) { + m_hEvent = CreateEvent(nullptr, FALSE, FALSE, nullptr); + if (m_hEvent == nullptr) { return -1; } ret = is_InitEvent(m_hCamera, m_hEvent, m_event); @@ -497,14 +497,14 @@ class vpUeyeGrabber::vpUeyeGrabberImpl void freeImages() { - m_pLastBuffer = NULL; + m_pLastBuffer = nullptr; // printf ("freeing image buffers\n"); for (unsigned int i = 0; i < sizeof(m_Images) / sizeof(m_Images[0]); i++) { - if (NULL != m_Images[i].pBuf) { + if (nullptr != m_Images[i].pBuf) { is_FreeImageMem(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID); } - m_Images[i].pBuf = NULL; + m_Images[i].pBuf = nullptr; m_Images[i].nImageID = 0; m_Images[i].nImageSeqNum = 0; } @@ -1027,14 +1027,14 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (auto_wb) { dblAutoWb = 0.0; - is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, NULL); + is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, nullptr); dblAutoWb = 1.0; - is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, NULL); + is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, nullptr); } else { dblAutoWb = 0.0; - is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, NULL); - is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, NULL); + is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, nullptr); + is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, nullptr); } } @@ -1124,7 +1124,7 @@ vpUeyeGrabber::~vpUeyeGrabber() { delete m_impl; } * Capture a new grayscale image. * * \param[out] I : Captured image. - * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 μs, or NULL if not + * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 μs, or nullptr if not * wanted. The time of image capture is defined as: * - The time when a (hardware or software) trigger event is received by the camera in trigger mode. * The delay between the receipt of the trigger signal and the start of exposure depends on the sensor. @@ -1149,7 +1149,7 @@ void vpUeyeGrabber::acquire(vpImage &I, double *timestamp_camera, /*! * Capture a new color image. * \param[out] I : Captured image. - * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 μs, or NULL if not + * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 μs, or nullptr if not * wanted. The time of image capture is defined as: * - The time when a (hardware or software) trigger event is received by the camera in trigger mode. * The delay between the receipt of the trigger signal and the start of exposure depends on the sensor. diff --git a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h index 3d161fac99..7f6e1c85de 100644 --- a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h +++ b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h @@ -38,7 +38,7 @@ class CameraList { public: - CameraList() : m_pCamList(NULL), m_CamInfo() + CameraList() : m_pCamList(nullptr), m_CamInfo() { // init the internal camera info structure ZeroMemory(&m_CamInfo, sizeof(UEYE_CAMERA_INFO)); @@ -73,7 +73,7 @@ class CameraList if (is_GetCameraList(m_pCamList) == IS_SUCCESS) { DWORD dw = m_pCamList->dwCount; delete m_pCamList; - m_pCamList = NULL; + m_pCamList = nullptr; if (dw) { // Reallocate the required camera list size @@ -101,7 +101,7 @@ class CameraList { if (m_pCamList) delete m_pCamList; - m_pCamList = NULL; + m_pCamList = nullptr; ZeroMemory(&m_CamInfo, sizeof(UEYE_CAMERA_INFO)); } diff --git a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp index 4047d0122c..543dd82d12 100644 --- a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp +++ b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp @@ -144,8 +144,8 @@ int main() */ vpV4l2Grabber::vpV4l2Grabber() - : fd(-1), device(), cap(), streamparm(), inp(NULL), std(NULL), fmt(NULL), ctl(NULL), fmt_v4l2(), fmt_me(), reqbufs(), - buf_v4l2(NULL), buf_me(NULL), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), + : fd(-1), device(), cap(), streamparm(), inp(nullptr), std(nullptr), fmt(nullptr), ctl(nullptr), fmt_v4l2(), fmt_me(), reqbufs(), + buf_v4l2(nullptr), buf_me(nullptr), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), streaming(false), m_input(vpV4l2Grabber::DEFAULT_INPUT), m_framerate(vpV4l2Grabber::framerate_25fps), m_frameformat(vpV4l2Grabber::V4L2_FRAME_FORMAT), m_pixelformat(vpV4l2Grabber::V4L2_YUYV_FORMAT) { @@ -200,8 +200,8 @@ vpV4l2Grabber::vpV4l2Grabber() */ vpV4l2Grabber::vpV4l2Grabber(bool verbose) - : fd(-1), device(), cap(), streamparm(), inp(NULL), std(NULL), fmt(NULL), ctl(NULL), fmt_v4l2(), fmt_me(), reqbufs(), - buf_v4l2(NULL), buf_me(NULL), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(verbose), m_nbuffers(3), field(0), + : fd(-1), device(), cap(), streamparm(), inp(nullptr), std(nullptr), fmt(nullptr), ctl(nullptr), fmt_v4l2(), fmt_me(), reqbufs(), + buf_v4l2(nullptr), buf_me(nullptr), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(verbose), m_nbuffers(3), field(0), streaming(false), m_input(vpV4l2Grabber::DEFAULT_INPUT), m_framerate(vpV4l2Grabber::framerate_25fps), m_frameformat(vpV4l2Grabber::V4L2_FRAME_FORMAT), m_pixelformat(vpV4l2Grabber::V4L2_YUYV_FORMAT) { @@ -246,8 +246,8 @@ vpV4l2Grabber::vpV4l2Grabber(bool verbose) \endcode */ vpV4l2Grabber::vpV4l2Grabber(unsigned input, unsigned scale) - : fd(-1), device(), cap(), streamparm(), inp(NULL), std(NULL), fmt(NULL), ctl(NULL), fmt_v4l2(), fmt_me(), reqbufs(), - buf_v4l2(NULL), buf_me(NULL), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), + : fd(-1), device(), cap(), streamparm(), inp(nullptr), std(nullptr), fmt(nullptr), ctl(nullptr), fmt_v4l2(), fmt_me(), reqbufs(), + buf_v4l2(nullptr), buf_me(nullptr), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), streaming(false), m_input(vpV4l2Grabber::DEFAULT_INPUT), m_framerate(vpV4l2Grabber::framerate_25fps), m_frameformat(vpV4l2Grabber::V4L2_FRAME_FORMAT), m_pixelformat(vpV4l2Grabber::V4L2_YUYV_FORMAT) { @@ -292,8 +292,8 @@ vpV4l2Grabber::vpV4l2Grabber(unsigned input, unsigned scale) \endcode */ vpV4l2Grabber::vpV4l2Grabber(vpImage &I, unsigned input, unsigned scale) - : fd(-1), device(), cap(), streamparm(), inp(NULL), std(NULL), fmt(NULL), ctl(NULL), fmt_v4l2(), fmt_me(), reqbufs(), - buf_v4l2(NULL), buf_me(NULL), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), + : fd(-1), device(), cap(), streamparm(), inp(nullptr), std(nullptr), fmt(nullptr), ctl(nullptr), fmt_v4l2(), fmt_me(), reqbufs(), + buf_v4l2(nullptr), buf_me(nullptr), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), streaming(false), m_input(vpV4l2Grabber::DEFAULT_INPUT), m_framerate(vpV4l2Grabber::framerate_25fps), m_frameformat(vpV4l2Grabber::V4L2_FRAME_FORMAT), m_pixelformat(vpV4l2Grabber::V4L2_YUYV_FORMAT) { @@ -341,8 +341,8 @@ vpV4l2Grabber::vpV4l2Grabber(vpImage &I, unsigned input, unsigned */ vpV4l2Grabber::vpV4l2Grabber(vpImage &I, unsigned input, unsigned scale) - : fd(-1), device(), cap(), streamparm(), inp(NULL), std(NULL), fmt(NULL), ctl(NULL), fmt_v4l2(), fmt_me(), reqbufs(), - buf_v4l2(NULL), buf_me(NULL), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), + : fd(-1), device(), cap(), streamparm(), inp(nullptr), std(nullptr), fmt(nullptr), ctl(nullptr), fmt_v4l2(), fmt_me(), reqbufs(), + buf_v4l2(nullptr), buf_me(nullptr), queue(0), waiton_cpt(0), index_buffer(0), m_verbose(false), m_nbuffers(3), field(0), streaming(false), m_input(vpV4l2Grabber::DEFAULT_INPUT), m_framerate(vpV4l2Grabber::framerate_25fps), m_frameformat(vpV4l2Grabber::V4L2_FRAME_FORMAT), m_pixelformat(vpV4l2Grabber::V4L2_YUYV_FORMAT) { @@ -853,29 +853,29 @@ void vpV4l2Grabber::close() fd = -1; } - if (inp != NULL) { + if (inp != nullptr) { delete [] inp; - inp = NULL; + inp = nullptr; } - if (std != NULL) { + if (std != nullptr) { delete [] std; - std = NULL; + std = nullptr; } - if (fmt != NULL) { + if (fmt != nullptr) { delete [] fmt; - fmt = NULL; + fmt = nullptr; } - if (ctl != NULL) { + if (ctl != nullptr) { delete [] ctl; - ctl = NULL; + ctl = nullptr; } - if (buf_v4l2 != NULL) { + if (buf_v4l2 != nullptr) { delete [] buf_v4l2; - buf_v4l2 = NULL; + buf_v4l2 = nullptr; } - if (buf_me != NULL) { + if (buf_me != nullptr) { delete [] buf_me; - buf_me = NULL; + buf_me = nullptr; } } @@ -912,29 +912,29 @@ void vpV4l2Grabber::open() throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Can't access to video device")); } - if (inp != NULL) { + if (inp != nullptr) { delete [] inp; - inp = NULL; + inp = nullptr; } - if (std != NULL) { + if (std != nullptr) { delete [] std; - std = NULL; + std = nullptr; } - if (fmt != NULL) { + if (fmt != nullptr) { delete [] fmt; - fmt = NULL; + fmt = nullptr; } - if (ctl != NULL) { + if (ctl != nullptr) { delete [] ctl; - ctl = NULL; + ctl = nullptr; } - if (buf_v4l2 != NULL) { + if (buf_v4l2 != nullptr) { delete [] buf_v4l2; - buf_v4l2 = NULL; + buf_v4l2 = nullptr; } - if (buf_me != NULL) { + if (buf_me != nullptr) { delete [] buf_me; - buf_me = NULL; + buf_me = nullptr; } inp = new struct v4l2_input[vpV4l2Grabber::MAX_INPUTS]; @@ -1194,7 +1194,7 @@ void vpV4l2Grabber::startStreaming() memcpy(&buf_me[i].fmt, &fmt_me, sizeof(ng_video_fmt)); buf_me[i].size = buf_me[i].fmt.bytesperline * buf_me[i].fmt.height; - buf_me[i].data = (unsigned char *)v4l2_mmap(NULL, buf_v4l2[i].length, PROT_READ | PROT_WRITE, MAP_SHARED, fd, + buf_me[i].data = (unsigned char *)v4l2_mmap(nullptr, buf_v4l2[i].length, PROT_READ | PROT_WRITE, MAP_SHARED, fd, (off_t)buf_v4l2[i].m.offset); if (buf_me[i].data == MAP_FAILED) { @@ -1252,7 +1252,7 @@ void vpV4l2Grabber::stopStreaming() } /*! - Fill the next buffer. If all the buffers are filled return NULL. + Fill the next buffer. If all the buffers are filled return nullptr. Update the buffer index. If all the buffers are filled index is set to -1. @@ -1277,17 +1277,17 @@ unsigned char *vpV4l2Grabber::waiton(__u32 &index, struct timeval ×tamp) tv.tv_usec = 0; FD_ZERO(&rdset); FD_SET(static_cast(fd), &rdset); - switch (select(fd + 1, &rdset, NULL, NULL, &tv)) { + switch (select(fd + 1, &rdset, nullptr, nullptr, &tv)) { case -1: if (EINTR == errno) goto again; index = 0; throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Can't access to the frame")); - return NULL; + return nullptr; case 0: index = 0; throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Can't access to the frame: timeout")); - return NULL; + return nullptr; } /* get it */ @@ -1310,7 +1310,7 @@ unsigned char *vpV4l2Grabber::waiton(__u32 &index, struct timeval ×tamp) throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "VIDIOC_DQBUF")); break; } - return NULL; + return nullptr; } waiton_cpt++; diff --git a/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp b/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp index 6037e9bd39..bd983c069a 100644 --- a/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp +++ b/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp @@ -66,7 +66,7 @@ body messages. */ vpSickLDMRS::vpSickLDMRS() - : socket_fd(-1), body(NULL), vAngle(), time_offset(0), isFirstMeasure(true), maxlen_body(104000) + : socket_fd(-1), body(nullptr), vAngle(), time_offset(0), isFirstMeasure(true), maxlen_body(104000) { ip = "131.254.12.119"; port = 12002; @@ -135,7 +135,7 @@ bool vpSickLDMRS::setup() tv.tv_usec = 0; FD_ZERO(&myset); FD_SET(static_cast(socket_fd), &myset); - res = select(socket_fd + 1, NULL, &myset, NULL, &tv); + res = select(socket_fd + 1, nullptr, &myset, nullptr, &tv); if (res < 0 && errno != EINTR) { fprintf(stderr, "Error connecting to server %d - %s\n", errno, strerror(errno)); return false; diff --git a/modules/sensor/src/mocap/vpMocapQualisys.cpp b/modules/sensor/src/mocap/vpMocapQualisys.cpp index 6e3d09cc19..6b88f638e8 100644 --- a/modules/sensor/src/mocap/vpMocapQualisys.cpp +++ b/modules/sensor/src/mocap/vpMocapQualisys.cpp @@ -117,7 +117,7 @@ class vpMocapQualisys::vpMocapQualisysImpl } else { for (auto i = 0; i < 6; i++) { if (!m_streamFrames) { - if (!m_rtProtocol.StreamFrames(CRTProtocol::RateAllFrames, 0, m_udpPort, NULL, CRTProtocol::cComponent6d)) { + if (!m_rtProtocol.StreamFrames(CRTProtocol::RateAllFrames, 0, m_udpPort, nullptr, CRTProtocol::cComponent6d)) { if (m_verbose) { std::cout << "Streaming frames error: " << m_rtProtocol.GetErrorString() << std::endl; } diff --git a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp index b5e8ac3fc8..6e3c05d3d7 100644 --- a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp +++ b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp @@ -67,7 +67,7 @@ vpOccipitalStructure::~vpOccipitalStructure() { close(); } Acquire greyscale image from Structure Core device. \param gray : Greyscale image. \param undistorted : Set to true to get undistorted grayscale image. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(vpImage &gray, bool undistorted, double *ts) { @@ -80,7 +80,7 @@ void vpOccipitalStructure::acquire(vpImage &gray, bool undistorte else memcpy(gray.bitmap, m_delegate.m_visibleFrame.undistorted().yData(), m_delegate.m_visibleFrame.ySize()); - if (ts != NULL) + if (ts != nullptr) *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); } @@ -91,7 +91,7 @@ void vpOccipitalStructure::acquire(vpImage &gray, bool undistorte Acquire color image from Structure Core device. \param rgb : RGB image. \param undistorted : Set to true to get undistorted image. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(vpImage &rgb, bool undistorted, double *ts) { @@ -117,7 +117,7 @@ void vpOccipitalStructure::acquire(vpImage &rgb, bool undistorted, doubl m_delegate.m_visibleFrame.width() * m_delegate.m_visibleFrame.height()); } - if (ts != NULL) + if (ts != nullptr) *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); } @@ -126,12 +126,12 @@ void vpOccipitalStructure::acquire(vpImage &rgb, bool undistorted, doubl /*! Acquire rgb image and IMU data from Structure Core device. - \param rgb : RGB image or NULL if not wanted. - \param depth : Depth image or NULL if not wanted. - \param acceleration_data : Acceleration data or NULL if not wanted. - \param gyroscope_data : Gyroscope data or NULL if not wanted. + \param rgb : RGB image or nullptr if not wanted. + \param depth : Depth image or nullptr if not wanted. + \param acceleration_data : Acceleration data or nullptr if not wanted. + \param gyroscope_data : Gyroscope data or nullptr if not wanted. \param undistorted : Set to true to get undistorted image. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(vpImage *rgb, vpImage *depth, vpColVector *acceleration_data, vpColVector *gyroscope_data, bool undistorted, double *ts) @@ -139,7 +139,7 @@ void vpOccipitalStructure::acquire(vpImage *rgb, vpImage *depth, std::unique_lock u(m_delegate.m_sampleLock); m_delegate.cv_sampleLock.wait(u); - if (rgb != NULL && m_delegate.m_visibleFrame.isValid()) { + if (rgb != nullptr && m_delegate.m_visibleFrame.isValid()) { // Detecting if it's a Color Structure Core device. if (m_delegate.m_cameraType == ST::StructureCoreCameraType::Color) vpImageConvert::RGBToRGBa(const_cast(m_delegate.m_visibleFrame.rgbData()), @@ -158,29 +158,29 @@ void vpOccipitalStructure::acquire(vpImage *rgb, vpImage *depth, m_delegate.m_visibleFrame.width() * m_delegate.m_visibleFrame.height()); } - if (ts != NULL) + if (ts != nullptr) *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); } - if (depth != NULL && m_delegate.m_depthFrame.isValid()) + if (depth != nullptr && m_delegate.m_depthFrame.isValid()) memcpy((unsigned char *)depth->bitmap, m_delegate.m_depthFrame.convertDepthToRgba(), m_delegate.m_depthFrame.width() * m_delegate.m_depthFrame.height() * 4); - if (acceleration_data != NULL) { + if (acceleration_data != nullptr) { ST::Acceleration accel = m_delegate.m_accelerometerEvent.acceleration(); acceleration_data[0] = accel.x; acceleration_data[1] = accel.y; acceleration_data[2] = accel.z; } - if (gyroscope_data != NULL) { + if (gyroscope_data != nullptr) { ST::RotationRate gyro_data = m_delegate.m_gyroscopeEvent.rotationRate(); gyroscope_data[0] = gyro_data.x; gyroscope_data[1] = gyro_data.y; gyroscope_data[2] = gyro_data.z; } - if (ts != NULL) // By default, frames are synchronized. + if (ts != nullptr) // By default, frames are synchronized. *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); u.unlock(); @@ -188,12 +188,12 @@ void vpOccipitalStructure::acquire(vpImage *rgb, vpImage *depth, /*! Acquire grayscale image, depth and IMU data from Structure Core device. - \param gray : Gray image or NULL if not wanted. - \param depth : Depth image or NULL if not wanted. - \param acceleration_data : Acceleration data or NULL if not wanted. - \param gyroscope_data : Gyroscope data or NULL if not wanted. + \param gray : Gray image or nullptr if not wanted. + \param depth : Depth image or nullptr if not wanted. + \param acceleration_data : Acceleration data or nullptr if not wanted. + \param gyroscope_data : Gyroscope data or nullptr if not wanted. \param undistorted : Set to true to get undistorted image. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(vpImage *gray, vpImage *depth, vpColVector *acceleration_data, vpColVector *gyroscope_data, bool undistorted, double *ts) @@ -201,35 +201,35 @@ void vpOccipitalStructure::acquire(vpImage *gray, vpImage std::unique_lock u(m_delegate.m_sampleLock); m_delegate.cv_sampleLock.wait(u); - if (gray != NULL && m_delegate.m_visibleFrame.isValid()) { + if (gray != nullptr && m_delegate.m_visibleFrame.isValid()) { if (!undistorted) memcpy(gray->bitmap, m_delegate.m_visibleFrame.yData(), m_delegate.m_visibleFrame.ySize()); else memcpy(gray->bitmap, m_delegate.m_visibleFrame.undistorted().yData(), m_delegate.m_visibleFrame.ySize()); - if (ts != NULL) + if (ts != nullptr) *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); } - if (depth != NULL && m_delegate.m_depthFrame.isValid()) + if (depth != nullptr && m_delegate.m_depthFrame.isValid()) memcpy((unsigned char *)depth->bitmap, m_delegate.m_depthFrame.convertDepthToRgba(), m_delegate.m_depthFrame.width() * m_delegate.m_depthFrame.height() * 4); - if (acceleration_data != NULL) { + if (acceleration_data != nullptr) { ST::Acceleration accel = m_delegate.m_accelerometerEvent.acceleration(); acceleration_data[0] = accel.x; acceleration_data[1] = accel.y; acceleration_data[2] = accel.z; } - if (gyroscope_data != NULL) { + if (gyroscope_data != nullptr) { ST::RotationRate gyro_data = m_delegate.m_gyroscopeEvent.rotationRate(); gyroscope_data[0] = gyro_data.x; gyroscope_data[1] = gyro_data.y; gyroscope_data[2] = gyro_data.z; } - if (ts != NULL) // By default, frames are synchronized. + if (ts != nullptr) // By default, frames are synchronized. *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); u.unlock(); @@ -237,14 +237,14 @@ void vpOccipitalStructure::acquire(vpImage *gray, vpImage /*! Acquire data from Structure Core device. - \param data_image : Visible image buffer or NULL if not wanted. - \param data_depth : Depth image buffer in millimeters or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. - \param acceleration_data : Acceleration data or NULL if not wanted. - \param gyroscope_data : Gyroscope data or NULL if not wanted. + \param data_image : Visible image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer in millimeters or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. + \param acceleration_data : Acceleration data or nullptr if not wanted. + \param gyroscope_data : Gyroscope data or nullptr if not wanted. \param undistorted : Set to true if you want undistorted monochrome device image. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, unsigned char *const data_infrared, @@ -254,11 +254,11 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha std::unique_lock u(m_delegate.m_sampleLock); m_delegate.cv_sampleLock.wait(u); - if (m_delegate.m_depthFrame.isValid() && data_depth != NULL) + if (m_delegate.m_depthFrame.isValid() && data_depth != nullptr) memcpy(data_depth, m_delegate.m_depthFrame.depthInMillimeters(), m_delegate.m_depthFrame.width() * m_delegate.m_depthFrame.height() * sizeof(float)); - if (m_delegate.m_visibleFrame.isValid() && data_image != NULL) { + if (m_delegate.m_visibleFrame.isValid() && data_image != nullptr) { if (m_delegate.m_cameraType == ST::StructureCoreCameraType::Color) vpImageConvert::RGBToRGBa(const_cast(m_delegate.m_visibleFrame.rgbData()), reinterpret_cast(data_image), @@ -277,28 +277,28 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha } } - if (m_delegate.m_infraredFrame.isValid() && data_infrared != NULL) + if (m_delegate.m_infraredFrame.isValid() && data_infrared != nullptr) memcpy(data_infrared, m_delegate.m_infraredFrame.data(), m_delegate.m_infraredFrame.width() * m_delegate.m_infraredFrame.height() * sizeof(uint16_t)); - if (data_pointCloud != NULL) + if (data_pointCloud != nullptr) getPointcloud(*data_pointCloud); - if (acceleration_data != NULL) { + if (acceleration_data != nullptr) { ST::Acceleration accel = m_delegate.m_accelerometerEvent.acceleration(); acceleration_data[0] = accel.x; acceleration_data[1] = accel.y; acceleration_data[2] = accel.z; } - if (gyroscope_data != NULL) { + if (gyroscope_data != nullptr) { ST::RotationRate gyro_data = m_delegate.m_gyroscopeEvent.rotationRate(); gyroscope_data[0] = gyro_data.x; gyroscope_data[1] = gyro_data.y; gyroscope_data[2] = gyro_data.z; } - if (ts != NULL) // By default, frames are synchronized. + if (ts != nullptr) // By default, frames are synchronized. *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); u.unlock(); @@ -307,15 +307,15 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha #ifdef VISP_HAVE_PCL /*! Acquire data from Structure Core device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. - \param pointcloud : Point cloud (in PCL format and without texture information) pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. - \param acceleration_data : Acceleration data or NULL if not wanted. - \param gyroscope_data : Gyroscope data or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. + \param pointcloud : Point cloud (in PCL format and without texture information) pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. + \param acceleration_data : Acceleration data or nullptr if not wanted. + \param gyroscope_data : Gyroscope data or nullptr if not wanted. \param undistorted : Set to true if you want undistorted monochrome device image. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, @@ -345,35 +345,35 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha } } - if (m_delegate.m_depthFrame.isValid() && data_depth != NULL) + if (m_delegate.m_depthFrame.isValid() && data_depth != nullptr) memcpy(data_depth, m_delegate.m_depthFrame.depthInMillimeters(), m_delegate.m_depthFrame.width() * m_delegate.m_depthFrame.height() * sizeof(float)); - if (m_delegate.m_infraredFrame.isValid() && data_infrared != NULL) + if (m_delegate.m_infraredFrame.isValid() && data_infrared != nullptr) memcpy(data_infrared, m_delegate.m_infraredFrame.data(), m_delegate.m_infraredFrame.width() * m_delegate.m_infraredFrame.height() * sizeof(uint16_t)); - if (data_pointCloud != NULL) + if (data_pointCloud != nullptr) getPointcloud(*data_pointCloud); - if (m_delegate.m_depthFrame.isValid() && pointcloud != NULL) + if (m_delegate.m_depthFrame.isValid() && pointcloud != nullptr) getPointcloud(pointcloud); - if (acceleration_data != NULL) { + if (acceleration_data != nullptr) { ST::Acceleration accel = m_delegate.m_accelerometerEvent.acceleration(); acceleration_data[0] = accel.x; acceleration_data[1] = accel.y; acceleration_data[2] = accel.z; } - if (gyroscope_data != NULL) { + if (gyroscope_data != nullptr) { ST::RotationRate gyro_data = m_delegate.m_gyroscopeEvent.rotationRate(); gyroscope_data[0] = gyro_data.x; gyroscope_data[1] = gyro_data.y; gyroscope_data[2] = gyro_data.z; } - if (ts != NULL) // By default, frames are synchronized. + if (ts != nullptr) // By default, frames are synchronized. *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); u.unlock(); @@ -381,15 +381,15 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha /*! Acquire data from Structure Core device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. - \param pointcloud : Point cloud (in PCL format) pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. - \param acceleration_data : Acceleration data or NULL if not wanted. - \param gyroscope_data : Gyroscope data or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. + \param pointcloud : Point cloud (in PCL format) pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. + \param acceleration_data : Acceleration data or nullptr if not wanted. + \param gyroscope_data : Gyroscope data or nullptr if not wanted. \param undistorted : Set to true if you want undistorted monochrome device image. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, @@ -400,11 +400,11 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha std::unique_lock u(m_delegate.m_sampleLock); m_delegate.cv_sampleLock.wait(u); - if (m_delegate.m_depthFrame.isValid() && data_depth != NULL) + if (m_delegate.m_depthFrame.isValid() && data_depth != nullptr) memcpy(data_depth, m_delegate.m_depthFrame.depthInMillimeters(), m_delegate.m_depthFrame.width() * m_delegate.m_depthFrame.height() * sizeof(float)); - if (m_delegate.m_visibleFrame.isValid() && data_image != NULL) { + if (m_delegate.m_visibleFrame.isValid() && data_image != nullptr) { if (m_delegate.m_cameraType == ST::StructureCoreCameraType::Color) vpImageConvert::RGBToRGBa(const_cast(m_delegate.m_visibleFrame.rgbData()), reinterpret_cast(data_image), @@ -423,31 +423,31 @@ void vpOccipitalStructure::acquire(unsigned char *const data_image, unsigned cha } } - if (m_delegate.m_infraredFrame.isValid() && data_infrared != NULL) + if (m_delegate.m_infraredFrame.isValid() && data_infrared != nullptr) memcpy(data_infrared, m_delegate.m_infraredFrame.data(), m_delegate.m_infraredFrame.width() * m_delegate.m_infraredFrame.height() * sizeof(uint16_t)); - if (m_delegate.m_depthFrame.isValid() && data_pointCloud != NULL) + if (m_delegate.m_depthFrame.isValid() && data_pointCloud != nullptr) getPointcloud(*data_pointCloud); - if (m_delegate.m_depthFrame.isValid() && m_delegate.m_visibleFrame.isValid() && pointcloud != NULL) + if (m_delegate.m_depthFrame.isValid() && m_delegate.m_visibleFrame.isValid() && pointcloud != nullptr) getColoredPointcloud(pointcloud); - if (acceleration_data != NULL) { + if (acceleration_data != nullptr) { ST::Acceleration accel = m_delegate.m_accelerometerEvent.acceleration(); acceleration_data[0] = accel.x; acceleration_data[1] = accel.y; acceleration_data[2] = accel.z; } - if (gyroscope_data != NULL) { + if (gyroscope_data != nullptr) { ST::RotationRate gyro_data = m_delegate.m_gyroscopeEvent.rotationRate(); gyroscope_data[0] = gyro_data.x; gyroscope_data[1] = gyro_data.y; gyroscope_data[2] = gyro_data.z; } - if (ts != NULL) // By default, frames are synchronized. + if (ts != nullptr) // By default, frames are synchronized. *ts = m_delegate.m_visibleFrame.arrivalTimestamp(); u.unlock(); @@ -481,7 +481,7 @@ void vpOccipitalStructure::getIMUVelocity(vpColVector *imu_vel, double *ts) std::unique_lock u(m_delegate.m_sampleLock); m_delegate.cv_sampleLock.wait(u); - if (imu_vel != NULL) { + if (imu_vel != nullptr) { imu_vel->resize(3, false); ST::RotationRate imu_rotationRate = m_delegate.m_gyroscopeEvent.rotationRate(); (*imu_vel)[0] = imu_rotationRate.x; @@ -489,7 +489,7 @@ void vpOccipitalStructure::getIMUVelocity(vpColVector *imu_vel, double *ts) (*imu_vel)[2] = imu_rotationRate.z; } - if (ts != NULL) + if (ts != nullptr) *ts = m_delegate.m_gyroscopeEvent.arrivalTimestamp(); u.unlock(); @@ -521,7 +521,7 @@ void vpOccipitalStructure::getIMUAcceleration(vpColVector *imu_acc, double *ts) std::unique_lock u(m_delegate.m_sampleLock); m_delegate.cv_sampleLock.wait(u); - if (imu_acc != NULL) { + if (imu_acc != nullptr) { imu_acc->resize(3, false); ST::Acceleration imu_acceleration = m_delegate.m_accelerometerEvent.acceleration(); (*imu_acc)[0] = imu_acceleration.x; @@ -529,7 +529,7 @@ void vpOccipitalStructure::getIMUAcceleration(vpColVector *imu_acc, double *ts) (*imu_acc)[2] = imu_acceleration.z; } - if (ts != NULL) + if (ts != nullptr) *ts = m_delegate.m_accelerometerEvent.arrivalTimestamp(); u.unlock(); @@ -564,7 +564,7 @@ void vpOccipitalStructure::getIMUData(vpColVector *imu_vel, vpColVector *imu_acc m_delegate.cv_sampleLock.wait(u); double imu_vel_timestamp, imu_acc_timestamp; - if (imu_vel != NULL) { + if (imu_vel != nullptr) { imu_vel->resize(3, false); ST::RotationRate imu_rotationRate = m_delegate.m_gyroscopeEvent.rotationRate(); (*imu_vel)[0] = imu_rotationRate.x; @@ -574,7 +574,7 @@ void vpOccipitalStructure::getIMUData(vpColVector *imu_vel, vpColVector *imu_acc m_delegate.m_gyroscopeEvent.arrivalTimestamp(); // Relative to an unspecified epoch. (see documentation). } - if (imu_acc != NULL) { + if (imu_acc != nullptr) { imu_acc->resize(3, false); ST::Acceleration imu_acceleration = m_delegate.m_accelerometerEvent.acceleration(); (*imu_acc)[0] = imu_acceleration.x; @@ -583,7 +583,7 @@ void vpOccipitalStructure::getIMUData(vpColVector *imu_vel, vpColVector *imu_acc imu_acc_timestamp = m_delegate.m_accelerometerEvent.arrivalTimestamp(); } - if (ts != NULL) + if (ts != nullptr) *ts = std::max(imu_vel_timestamp, imu_acc_timestamp); u.unlock(); diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp index b1b084f5af..f0605385d8 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp @@ -47,7 +47,7 @@ * Default constructor. */ vpRealSense::vpRealSense() - : m_context(), m_device(NULL), m_num_devices(0), m_serial_no(), m_intrinsics(), m_max_Z(8), m_enableStreams(), + : m_context(), m_device(nullptr), m_num_devices(0), m_serial_no(), m_intrinsics(), m_max_Z(8), m_enableStreams(), m_useStreamPresets(), m_streamPresets(), m_streamParams(), m_invalidDepthValue(0.0f) { initStream(); @@ -120,7 +120,7 @@ void vpRealSense::open() } // Exit with error if no camera is detected that matches the input serial // number. - if ((!m_serial_no.empty()) && (m_device == NULL)) { + if ((!m_serial_no.empty()) && (m_device == nullptr)) { throw vpException(vpException::fatalError, "RealSense Camera - No camera detected with input " "serial_no \"%s\" Exiting!", @@ -245,7 +245,7 @@ void vpRealSense::close() if (m_device->is_streaming()) { m_device->stop(); } - m_device = NULL; + m_device = nullptr; } } @@ -376,7 +376,7 @@ vpHomogeneousMatrix vpRealSense::getTransformation(const rs::stream &from, const */ void vpRealSense::acquire(vpImage &grey) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -398,7 +398,7 @@ void vpRealSense::acquire(vpImage &grey) */ void vpRealSense::acquire(vpImage &grey, std::vector &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -422,7 +422,7 @@ void vpRealSense::acquire(vpImage &grey, std::vector */ void vpRealSense::acquire(std::vector &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -441,7 +441,7 @@ void vpRealSense::acquire(std::vector &pointcloud) */ void vpRealSense::acquire(vpImage &color) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -466,7 +466,7 @@ void vpRealSense::acquire(vpImage &color) void vpRealSense::acquire(vpImage &color, vpImage &infrared, vpImage &depth, std::vector &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -500,7 +500,7 @@ void vpRealSense::acquire(vpImage &color, vpImage &infrared, v void vpRealSense::acquire(vpImage &grey, vpImage &infrared, vpImage &depth, std::vector &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -531,7 +531,7 @@ void vpRealSense::acquire(vpImage &grey, vpImage &infra */ void vpRealSense::acquire(vpImage &color, std::vector &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -549,12 +549,12 @@ void vpRealSense::acquire(vpImage &color, std::vector &poin /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. \param data_infrared2 : Infrared (for the second IR camera if available) - image buffer or NULL if not wanted. \param stream_color : Type of color + image buffer or nullptr if not wanted. \param stream_color : Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth). \param stream_depth : Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, @@ -570,7 +570,7 @@ void vpRealSense::acquire(unsigned char *const data_image, unsigned char *const const rs::stream &stream_depth, const rs::stream &stream_infrared, const rs::stream &stream_infrared2) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } @@ -580,23 +580,23 @@ void vpRealSense::acquire(unsigned char *const data_image, unsigned char *const m_device->wait_for_frames(); - if (data_image != NULL) { + if (data_image != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::color, data_image, stream_color); } - if (data_depth != NULL) { + if (data_depth != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::depth, data_depth, stream_depth); - if (data_pointCloud != NULL) { + if (data_pointCloud != nullptr) { vp_rs_get_pointcloud_impl(m_device, m_intrinsics, m_max_Z, *data_pointCloud, m_invalidDepthValue, stream_depth); } } - if (data_infrared != NULL) { + if (data_infrared != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::infrared, data_infrared, stream_infrared); } - if (data_infrared2 != NULL) { + if (data_infrared2 != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::infrared2, data_infrared2, stream_infrared2); } } @@ -677,7 +677,7 @@ void vpRealSense::setEnableStream(const rs::stream &stream, bool status) { m_ena */ void vpRealSense::acquire(pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -696,7 +696,7 @@ void vpRealSense::acquire(pcl::PointCloud::Ptr &pointcloud) */ void vpRealSense::acquire(pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -716,7 +716,7 @@ void vpRealSense::acquire(pcl::PointCloud::Ptr &pointcloud) */ void vpRealSense::acquire(vpImage &grey, pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -739,7 +739,7 @@ void vpRealSense::acquire(vpImage &grey, pcl::PointCloud &color, pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -765,7 +765,7 @@ void vpRealSense::acquire(vpImage &color, pcl::PointCloud void vpRealSense::acquire(vpImage &color, vpImage &infrared, vpImage &depth, pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -797,7 +797,7 @@ void vpRealSense::acquire(vpImage &color, vpImage &infrared, v void vpRealSense::acquire(vpImage &grey, vpImage &infrared, vpImage &depth, pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -829,7 +829,7 @@ void vpRealSense::acquire(vpImage &grey, vpImage &infra void vpRealSense::acquire(vpImage &color, vpImage &infrared, vpImage &depth, pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -861,7 +861,7 @@ void vpRealSense::acquire(vpImage &color, vpImage &infrared, v void vpRealSense::acquire(vpImage &grey, vpImage &infrared, vpImage &depth, pcl::PointCloud::Ptr &pointcloud) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } if (!m_device->is_streaming()) { @@ -885,13 +885,13 @@ void vpRealSense::acquire(vpImage &grey, vpImage &infra /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. \param pointcloud : Point cloud (in PCL format and without texture - information) pointer or NULL if not wanted. \param data_infrared : Infrared - image buffer or NULL if not wanted. \param data_infrared2 : Infrared (for - the second IR camera if available) image buffer or NULL if not wanted. + information) pointer or nullptr if not wanted. \param data_infrared : Infrared + image buffer or nullptr if not wanted. \param data_infrared2 : Infrared (for + the second IR camera if available) image buffer or nullptr if not wanted. \param stream_color : Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth). \param stream_depth : Type of depth stream (e.g. rs::stream::depth, @@ -909,7 +909,7 @@ void vpRealSense::acquire(unsigned char *const data_image, unsigned char *const const rs::stream &stream_depth, const rs::stream &stream_infrared, const rs::stream &stream_infrared2) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } @@ -919,40 +919,40 @@ void vpRealSense::acquire(unsigned char *const data_image, unsigned char *const m_device->wait_for_frames(); - if (data_image != NULL) { + if (data_image != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::color, data_image, stream_color); } - if (data_depth != NULL) { + if (data_depth != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::depth, data_depth, stream_depth); } - if (data_pointCloud != NULL) { + if (data_pointCloud != nullptr) { vp_rs_get_pointcloud_impl(m_device, m_intrinsics, m_max_Z, *data_pointCloud, m_invalidDepthValue, stream_depth); } - if (pointcloud != NULL) { + if (pointcloud != nullptr) { vp_rs_get_pointcloud_impl(m_device, m_intrinsics, m_max_Z, pointcloud, m_invalidDepthValue, stream_depth); } - if (data_infrared != NULL) { + if (data_infrared != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::infrared, data_infrared, stream_infrared); } - if (data_infrared2 != NULL) { + if (data_infrared2 != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::infrared2, data_infrared2, stream_infrared2); } } /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. \param pointcloud : Point cloud (in PCL format and with texture information) - pointer or NULL if not wanted. \param data_infrared : Infrared image buffer - or NULL if not wanted. \param data_infrared2 : Infrared (for the second IR - camera if available) image buffer or NULL if not wanted. \param stream_color + pointer or nullptr if not wanted. \param data_infrared : Infrared image buffer + or nullptr if not wanted. \param data_infrared2 : Infrared (for the second IR + camera if available) image buffer or nullptr if not wanted. \param stream_color : Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth). \param stream_depth : Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, @@ -969,7 +969,7 @@ void vpRealSense::acquire(unsigned char *const data_image, unsigned char *const const rs::stream &stream_depth, const rs::stream &stream_infrared, const rs::stream &stream_infrared2) { - if (m_device == NULL) { + if (m_device == nullptr) { throw vpException(vpException::fatalError, "RealSense Camera - Device not opened!"); } @@ -979,28 +979,28 @@ void vpRealSense::acquire(unsigned char *const data_image, unsigned char *const m_device->wait_for_frames(); - if (data_image != NULL) { + if (data_image != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::color, data_image, stream_color); } - if (data_depth != NULL) { + if (data_depth != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::depth, data_depth, stream_depth); } - if (data_pointCloud != NULL) { + if (data_pointCloud != nullptr) { vp_rs_get_pointcloud_impl(m_device, m_intrinsics, m_max_Z, *data_pointCloud, m_invalidDepthValue, stream_depth); } - if (pointcloud != NULL) { + if (pointcloud != nullptr) { vp_rs_get_pointcloud_impl(m_device, m_intrinsics, m_max_Z, pointcloud, m_invalidDepthValue, stream_color, stream_depth); } - if (data_infrared != NULL) { + if (data_infrared != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::infrared, data_infrared, stream_infrared); } - if (data_infrared2 != NULL) { + if (data_infrared2 != nullptr) { vp_rs_get_native_frame_data_impl(m_device, m_intrinsics, rs::stream::infrared2, data_infrared2, stream_infrared2); } } diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp index 4ed0468df4..93a918cf3a 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp @@ -82,14 +82,14 @@ vpRealSense2::~vpRealSense2() { close(); } /*! Acquire greyscale image from RealSense device. \param grey : Greyscale image. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(vpImage &grey, double *ts) { auto data = m_pipe.wait_for_frames(); auto color_frame = data.get_color_frame(); getGreyFrame(color_frame, grey); - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } } @@ -97,46 +97,46 @@ void vpRealSense2::acquire(vpImage &grey, double *ts) /*! Acquire color image from RealSense device. \param color : Color image. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(vpImage &color, double *ts) { auto data = m_pipe.wait_for_frames(); auto color_frame = data.get_color_frame(); getColorFrame(color_frame, color); - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } } /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. - \param align_to : Align to a reference stream or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. + \param align_to : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. - \param ts : Image timestamp or NULL if not wanted. + \param ts : Image timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, unsigned char *const data_infrared, rs2::align *const align_to, double *ts) { - acquire(data_image, data_depth, data_pointCloud, data_infrared, NULL, align_to, ts); + acquire(data_image, data_depth, data_pointCloud, data_infrared, nullptr, align_to, ts); } /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. - \param data_infrared1 : First infrared image buffer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. + \param data_infrared1 : First infrared image buffer or nullptr if not wanted. \param data_infrared2 : Second infrared image buffer (if supported by the device) - or NULL if not wanted. - \param align_to : Align to a reference stream or NULL if not wanted. + or nullptr if not wanted. + \param align_to : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. The following code shows how to use this function to get color, infrared 1 and infrared 2 frames acquired by a D435 device: @@ -169,7 +169,7 @@ int main() { #endif while (true) { - rs.acquire((unsigned char *) Ic.bitmap, NULL, NULL, Ii1.bitmap, Ii2.bitmap, NULL); + rs.acquire((unsigned char *) Ic.bitmap, nullptr, nullptr, Ii1.bitmap, Ii2.bitmap, nullptr); vpDisplay::display(Ic); vpDisplay::display(Ii1); vpDisplay::display(Ii2); @@ -188,7 +188,7 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const unsigned char *const data_infrared2, rs2::align *const align_to, double *ts) { auto data = m_pipe.wait_for_frames(); - if (align_to != NULL) { + if (align_to != nullptr) { // Infrared stream is not aligned // see https://github.com/IntelRealSense/librealsense/issues/1556#issuecomment-384919994 #if (RS2_API_VERSION > ((2 * 10000) + (9 * 100) + 0)) @@ -198,33 +198,33 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const #endif } - if (data_image != NULL) { + if (data_image != nullptr) { auto color_frame = data.get_color_frame(); getNativeFrameData(color_frame, data_image); } - if (data_depth != NULL || data_pointCloud != NULL) { + if (data_depth != nullptr || data_pointCloud != nullptr) { auto depth_frame = data.get_depth_frame(); - if (data_depth != NULL) { + if (data_depth != nullptr) { getNativeFrameData(depth_frame, data_depth); } - if (data_pointCloud != NULL) { + if (data_pointCloud != nullptr) { getPointcloud(depth_frame, *data_pointCloud); } } - if (data_infrared1 != NULL) { + if (data_infrared1 != nullptr) { auto infrared_frame = data.first(RS2_STREAM_INFRARED); getNativeFrameData(infrared_frame, data_infrared1); } - if (data_infrared2 != NULL) { + if (data_infrared2 != nullptr) { auto infrared_frame = data.get_infrared_frame(2); getNativeFrameData(infrared_frame, data_infrared2); } - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } } @@ -236,7 +236,7 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const \param right : Right image. \param ts : Data timestamp. - Pass NULL to one of these parameters if you don't want the corresponding data. + Pass nullptr to one of these parameters if you don't want the corresponding data. For example if you are only interested in the right fisheye image, use: \code @@ -247,14 +247,14 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const rs.open(config); vpImage I_right; - rs.acquire(NULL, &I_right, NULL, NULL); + rs.acquire(nullptr, &I_right, nullptr, nullptr); \endcode */ void vpRealSense2::acquire(vpImage *left, vpImage *right, double *ts) { auto data = m_pipe.wait_for_frames(); - if (left != NULL) { + if (left != nullptr) { auto left_fisheye_frame = data.get_fisheye_frame(1); unsigned int width = static_cast(left_fisheye_frame.get_width()); unsigned int height = static_cast(left_fisheye_frame.get_height()); @@ -262,7 +262,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage getNativeFrameData(left_fisheye_frame, (*left).bitmap); } - if (right != NULL) { + if (right != nullptr) { auto right_fisheye_frame = data.get_fisheye_frame(2); unsigned int width = static_cast(right_fisheye_frame.get_width()); unsigned int height = static_cast(right_fisheye_frame.get_height()); @@ -270,7 +270,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage getNativeFrameData(right_fisheye_frame, (*right).bitmap); } - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } } @@ -286,7 +286,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage \param confidence : Pose estimation confidence (1: Low, 2: Medium, 3: High). \param ts : Data timestamp. - Pass NULL to one of these parameters if you don't want the corresponding data. + Pass nullptr to one of these parameters if you don't want the corresponding data. For example if you are only interested in the pose, use: \code @@ -300,7 +300,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage rs.open(config); vpHomogeneousMatrix cMw; - rs.acquire(NULL, NULL, &cMw, NULL, NULL, NULL, NULL); + rs.acquire(nullptr, nullptr, &cMw, nullptr, nullptr, nullptr, nullptr); \endcode */ void vpRealSense2::acquire(vpImage *left, vpImage *right, vpHomogeneousMatrix *cMw, @@ -308,7 +308,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage { auto data = m_pipe.wait_for_frames(); - if (left != NULL) { + if (left != nullptr) { auto left_fisheye_frame = data.get_fisheye_frame(1); unsigned int width = static_cast(left_fisheye_frame.get_width()); unsigned int height = static_cast(left_fisheye_frame.get_height()); @@ -316,7 +316,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage getNativeFrameData(left_fisheye_frame, (*left).bitmap); } - if (right != NULL) { + if (right != nullptr) { auto right_fisheye_frame = data.get_fisheye_frame(2); unsigned int width = static_cast(right_fisheye_frame.get_width()); unsigned int height = static_cast(right_fisheye_frame.get_height()); @@ -327,11 +327,11 @@ void vpRealSense2::acquire(vpImage *left, vpImage auto pose_frame = data.first_or_default(RS2_STREAM_POSE); auto pose_data = pose_frame.as().get_pose_data(); - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } - if (cMw != NULL) { + if (cMw != nullptr) { m_pos[0] = static_cast(pose_data.translation.x); m_pos[1] = static_cast(pose_data.translation.y); m_pos[2] = static_cast(pose_data.translation.z); @@ -344,7 +344,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage *cMw = vpHomogeneousMatrix(m_pos, m_quat); } - if (odo_vel != NULL) { + if (odo_vel != nullptr) { odo_vel->resize(6, false); (*odo_vel)[0] = static_cast(pose_data.velocity.x); (*odo_vel)[1] = static_cast(pose_data.velocity.y); @@ -354,7 +354,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage (*odo_vel)[5] = static_cast(pose_data.angular_velocity.z); } - if (odo_acc != NULL) { + if (odo_acc != nullptr) { odo_acc->resize(6, false); (*odo_acc)[0] = static_cast(pose_data.acceleration.x); (*odo_acc)[1] = static_cast(pose_data.acceleration.y); @@ -364,7 +364,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage (*odo_acc)[5] = static_cast(pose_data.angular_acceleration.z); } - if (confidence != NULL) { + if (confidence != nullptr) { *confidence = pose_data.tracker_confidence; } } @@ -388,7 +388,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage { auto data = m_pipe.wait_for_frames(); - if (left != NULL) { + if (left != nullptr) { auto left_fisheye_frame = data.get_fisheye_frame(1); unsigned int width = static_cast(left_fisheye_frame.get_width()); unsigned int height = static_cast(left_fisheye_frame.get_height()); @@ -396,7 +396,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage getNativeFrameData(left_fisheye_frame, (*left).bitmap); } - if (right != NULL) { + if (right != nullptr) { auto right_fisheye_frame = data.get_fisheye_frame(2); unsigned int width = static_cast(right_fisheye_frame.get_width()); unsigned int height = static_cast(right_fisheye_frame.get_height()); @@ -407,11 +407,11 @@ void vpRealSense2::acquire(vpImage *left, vpImage auto pose_frame = data.first_or_default(RS2_STREAM_POSE); auto pose_data = pose_frame.as().get_pose_data(); - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } - if (cMw != NULL) { + if (cMw != nullptr) { m_pos[0] = static_cast(pose_data.translation.x); m_pos[1] = static_cast(pose_data.translation.y); m_pos[2] = static_cast(pose_data.translation.z); @@ -424,7 +424,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage *cMw = vpHomogeneousMatrix(m_pos, m_quat); } - if (odo_vel != NULL) { + if (odo_vel != nullptr) { odo_vel->resize(6, false); (*odo_vel)[0] = static_cast(pose_data.velocity.x); (*odo_vel)[1] = static_cast(pose_data.velocity.y); @@ -434,7 +434,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage (*odo_vel)[5] = static_cast(pose_data.angular_velocity.z); } - if (odo_acc != NULL) { + if (odo_acc != nullptr) { odo_acc->resize(6, false); (*odo_acc)[0] = static_cast(pose_data.acceleration.x); (*odo_acc)[1] = static_cast(pose_data.acceleration.y); @@ -447,7 +447,7 @@ void vpRealSense2::acquire(vpImage *left, vpImage auto accel_frame = data.first_or_default(RS2_STREAM_ACCEL); auto accel_data = accel_frame.as().get_motion_data(); - if (imu_acc != NULL) { + if (imu_acc != nullptr) { imu_acc->resize(3, false); (*imu_acc)[0] = static_cast(accel_data.x); (*imu_acc)[1] = static_cast(accel_data.y); @@ -457,14 +457,14 @@ void vpRealSense2::acquire(vpImage *left, vpImage auto gyro_frame = data.first_or_default(RS2_STREAM_GYRO); auto gyro_data = gyro_frame.as().get_motion_data(); - if (imu_vel != NULL) { + if (imu_vel != nullptr) { imu_vel->resize(3, false); (*imu_vel)[0] = static_cast(gyro_data.x); (*imu_vel)[1] = static_cast(gyro_data.y); (*imu_vel)[2] = static_cast(gyro_data.z); } - if (confidence != NULL) { + if (confidence != nullptr) { *confidence = pose_data.tracker_confidence; } } @@ -473,37 +473,37 @@ void vpRealSense2::acquire(vpImage *left, vpImage #ifdef VISP_HAVE_PCL /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. \param pointcloud : Point cloud (in PCL format and without texture - information) pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. - \param align_to : Align to a reference stream or NULL if not wanted. + information) pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. + \param align_to : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, unsigned char *const data_infrared, rs2::align *const align_to, double *ts) { - acquire(data_image, data_depth, data_pointCloud, pointcloud, data_infrared, NULL, align_to, ts); + acquire(data_image, data_depth, data_pointCloud, pointcloud, data_infrared, nullptr, align_to, ts); } /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. \param pointcloud : Point cloud (in PCL format and without texture - information) pointer or NULL if not wanted. - \param data_infrared1 : First infrared image buffer or NULL if not wanted. + information) pointer or nullptr if not wanted. + \param data_infrared1 : First infrared image buffer or nullptr if not wanted. \param data_infrared2 : Second infrared image (if supported by the device) - buffer or NULL if not wanted. - \param align_to : Align to a reference stream or NULL if not wanted. + buffer or nullptr if not wanted. + \param align_to : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, @@ -511,7 +511,7 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const unsigned char *const data_infrared2, rs2::align *const align_to, double *ts) { auto data = m_pipe.wait_for_frames(); - if (align_to != NULL) { + if (align_to != nullptr) { // Infrared stream is not aligned // see https://github.com/IntelRealSense/librealsense/issues/1556#issuecomment-384919994 #if (RS2_API_VERSION > ((2 * 10000) + (9 * 100) + 0)) @@ -521,74 +521,74 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const #endif } - if (data_image != NULL) { + if (data_image != nullptr) { auto color_frame = data.get_color_frame(); getNativeFrameData(color_frame, data_image); } - if (data_depth != NULL || data_pointCloud != NULL || pointcloud != NULL) { + if (data_depth != nullptr || data_pointCloud != nullptr || pointcloud != nullptr) { auto depth_frame = data.get_depth_frame(); - if (data_depth != NULL) { + if (data_depth != nullptr) { getNativeFrameData(depth_frame, data_depth); } - if (data_pointCloud != NULL) { + if (data_pointCloud != nullptr) { getPointcloud(depth_frame, *data_pointCloud); } - if (pointcloud != NULL) { + if (pointcloud != nullptr) { getPointcloud(depth_frame, pointcloud); } } - if (data_infrared1 != NULL) { + if (data_infrared1 != nullptr) { auto infrared_frame = data.first(RS2_STREAM_INFRARED); getNativeFrameData(infrared_frame, data_infrared1); } - if (data_infrared2 != NULL) { + if (data_infrared2 != nullptr) { auto infrared_frame = data.get_infrared_frame(2); getNativeFrameData(infrared_frame, data_infrared2); } - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } } /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. \param pointcloud : Point cloud (in PCL format and with texture information) - pointer or NULL if not wanted. - \param data_infrared : Infrared image buffer or NULL if not wanted. - \param align_to : Align to a reference stream or NULL if not wanted. + pointer or nullptr if not wanted. + \param data_infrared : Infrared image buffer or nullptr if not wanted. + \param align_to : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, pcl::PointCloud::Ptr &pointcloud, unsigned char *const data_infrared, rs2::align *const align_to, double *ts) { - acquire(data_image, data_depth, data_pointCloud, pointcloud, data_infrared, NULL, align_to, ts); + acquire(data_image, data_depth, data_pointCloud, pointcloud, data_infrared, nullptr, align_to, ts); } /*! Acquire data from RealSense device. - \param data_image : Color image buffer or NULL if not wanted. - \param data_depth : Depth image buffer or NULL if not wanted. - \param data_pointCloud : Point cloud vector pointer or NULL if not wanted. + \param data_image : Color image buffer or nullptr if not wanted. + \param data_depth : Depth image buffer or nullptr if not wanted. + \param data_pointCloud : Point cloud vector pointer or nullptr if not wanted. \param pointcloud : Point cloud (in PCL format and with texture information) - pointer or NULL if not wanted. - \param data_infrared1 : First infrared image buffer or NULL if not wanted. + pointer or nullptr if not wanted. + \param data_infrared1 : First infrared image buffer or nullptr if not wanted. \param data_infrared2 : Second infrared image (if supported by the device) - buffer or NULL if not wanted. - \param align_to : Align to a reference stream or NULL if not wanted. + buffer or nullptr if not wanted. + \param align_to : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. - \param ts : Data timestamp or NULL if not wanted. + \param ts : Data timestamp or nullptr if not wanted. */ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const data_depth, std::vector *const data_pointCloud, @@ -596,7 +596,7 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const unsigned char *const data_infrared2, rs2::align *const align_to, double *ts) { auto data = m_pipe.wait_for_frames(); - if (align_to != NULL) { + if (align_to != nullptr) { // Infrared stream is not aligned // see https://github.com/IntelRealSense/librealsense/issues/1556#issuecomment-384919994 #if (RS2_API_VERSION > ((2 * 10000) + (9 * 100) + 0)) @@ -607,36 +607,36 @@ void vpRealSense2::acquire(unsigned char *const data_image, unsigned char *const } auto color_frame = data.get_color_frame(); - if (data_image != NULL) { + if (data_image != nullptr) { getNativeFrameData(color_frame, data_image); } - if (data_depth != NULL || data_pointCloud != NULL || pointcloud != NULL) { + if (data_depth != nullptr || data_pointCloud != nullptr || pointcloud != nullptr) { auto depth_frame = data.get_depth_frame(); - if (data_depth != NULL) { + if (data_depth != nullptr) { getNativeFrameData(depth_frame, data_depth); } - if (data_pointCloud != NULL) { + if (data_pointCloud != nullptr) { getPointcloud(depth_frame, *data_pointCloud); } - if (pointcloud != NULL) { + if (pointcloud != nullptr) { getPointcloud(depth_frame, color_frame, pointcloud); } } - if (data_infrared1 != NULL) { + if (data_infrared1 != nullptr) { auto infrared_frame = data.first(RS2_STREAM_INFRARED); getNativeFrameData(infrared_frame, data_infrared1); } - if (data_infrared2 != NULL) { + if (data_infrared2 != nullptr) { auto infrared_frame = data.get_infrared_frame(2); getNativeFrameData(infrared_frame, data_infrared2); } - if (ts != NULL) { + if (ts != nullptr) { *ts = data.get_timestamp(); } } @@ -1187,10 +1187,10 @@ unsigned int vpRealSense2::getOdometryData(vpHomogeneousMatrix *cMw, vpColVector auto f = frame.first_or_default(RS2_STREAM_POSE); auto pose_data = f.as().get_pose_data(); - if (ts != NULL) + if (ts != nullptr) *ts = frame.get_timestamp(); - if (cMw != NULL) { + if (cMw != nullptr) { m_pos[0] = static_cast(pose_data.translation.x); m_pos[1] = static_cast(pose_data.translation.y); m_pos[2] = static_cast(pose_data.translation.z); @@ -1203,7 +1203,7 @@ unsigned int vpRealSense2::getOdometryData(vpHomogeneousMatrix *cMw, vpColVector *cMw = vpHomogeneousMatrix(m_pos, m_quat); } - if (odo_vel != NULL) { + if (odo_vel != nullptr) { odo_vel->resize(6, false); (*odo_vel)[0] = static_cast(pose_data.velocity.x); (*odo_vel)[1] = static_cast(pose_data.velocity.y); @@ -1213,7 +1213,7 @@ unsigned int vpRealSense2::getOdometryData(vpHomogeneousMatrix *cMw, vpColVector (*odo_vel)[5] = static_cast(pose_data.angular_velocity.z); } - if (odo_acc != NULL) { + if (odo_acc != nullptr) { odo_acc->resize(6, false); (*odo_acc)[0] = static_cast(pose_data.acceleration.x); (*odo_acc)[1] = static_cast(pose_data.acceleration.y); @@ -1252,10 +1252,10 @@ void vpRealSense2::getIMUAcceleration(vpColVector *imu_acc, double *ts) auto f = frame.first_or_default(RS2_STREAM_ACCEL); auto imu_acc_data = f.as().get_motion_data(); - if (ts != NULL) + if (ts != nullptr) *ts = f.get_timestamp(); - if (imu_acc != NULL) { + if (imu_acc != nullptr) { imu_acc->resize(3, false); (*imu_acc)[0] = static_cast(imu_acc_data.x); (*imu_acc)[1] = static_cast(imu_acc_data.y); @@ -1289,10 +1289,10 @@ void vpRealSense2::getIMUVelocity(vpColVector *imu_vel, double *ts) auto f = frame.first_or_default(RS2_STREAM_GYRO); auto imu_vel_data = f.as().get_motion_data(); - if (ts != NULL) + if (ts != nullptr) *ts = f.get_timestamp(); - if (imu_vel != NULL) { + if (imu_vel != nullptr) { imu_vel->resize(3, false); (*imu_vel)[0] = static_cast(imu_vel_data.x); (*imu_vel)[1] = static_cast(imu_vel_data.x); @@ -1324,10 +1324,10 @@ void vpRealSense2::getIMUData(vpColVector *imu_acc, vpColVector *imu_vel, double { auto data = m_pipe.wait_for_frames(); - if (ts != NULL) + if (ts != nullptr) *ts = data.get_timestamp(); - if (imu_acc != NULL) { + if (imu_acc != nullptr) { auto acc_data = data.first_or_default(RS2_STREAM_ACCEL); auto imu_acc_data = acc_data.as().get_motion_data(); @@ -1337,7 +1337,7 @@ void vpRealSense2::getIMUData(vpColVector *imu_acc, vpColVector *imu_vel, double (*imu_acc)[2] = static_cast(imu_acc_data.z); } - if (imu_vel != NULL) { + if (imu_vel != nullptr) { auto vel_data = data.first_or_default(RS2_STREAM_GYRO); auto imu_vel_data = vel_data.as().get_motion_data(); diff --git a/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp index f7a7cbd995..f3f93f1d66 100755 --- a/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp @@ -82,7 +82,7 @@ int main(int argc, char **argv) } #if defined(VISP_HAVE_DISPLAY) - vpPlot *plotter = NULL; + vpPlot *plotter = nullptr; if (!opt_no_display) { plotter = new vpPlot(2, 700, 700, 100, 200, "Curves..."); plotter->initGraph(0, 3); diff --git a/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp index a8a626e1a7..ce6eea2e85 100644 --- a/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp @@ -66,7 +66,7 @@ int main(int argc, char **argv) vpForceTorqueIitSensor iit_ft; #if defined(VISP_HAVE_DISPLAY) - vpPlot *plotter = NULL; + vpPlot *plotter = nullptr; if (!opt_no_display) { plotter = new vpPlot(2, 700, 700, 100, 200, "Curves..."); plotter->initGraph(0, 3); diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp index d585e7d3bc..c591caed22 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp @@ -85,7 +85,7 @@ int main() pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud); - sc.acquire((unsigned char *)I_visible.bitmap, NULL, NULL, pointcloud); + sc.acquire((unsigned char *)I_visible.bitmap, nullptr, nullptr, pointcloud); pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer")); pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud); @@ -98,7 +98,7 @@ int main() double t = vpTime::measureTimeMs(); // Acquire depth as point cloud. - sc.acquire((unsigned char *)I_visible.bitmap, NULL, NULL, pointcloud); + sc.acquire((unsigned char *)I_visible.bitmap, nullptr, nullptr, pointcloud); vpDisplay::display(I_visible); vpDisplay::displayText(I_visible, 15 * display_scale, 15 * display_scale, "Click to quit", vpColor::red); vpDisplay::flush(I_visible); diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp index 85b2c97c06..39073eb05f 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp @@ -100,7 +100,7 @@ int main(int argc, char *argv[]) rs.acquire(reinterpret_cast(color.bitmap), reinterpret_cast(depth_raw.bitmap), &pointcloud_colvector, reinterpret_cast(infrared1.bitmap), - reinterpret_cast(infrared2.bitmap), NULL); + reinterpret_cast(infrared2.bitmap), nullptr); vpImageConvert::createDepthHistogram(depth_raw, depth_color); @@ -160,7 +160,7 @@ int main(int argc, char *argv[]) double t = vpTime::measureTimeMs(); rs.acquire(reinterpret_cast(color.bitmap), reinterpret_cast(depth_raw.bitmap), - NULL, reinterpret_cast(infrared1.bitmap)); + nullptr, reinterpret_cast(infrared1.bitmap)); vpImageConvert::createDepthHistogram(depth_raw, depth_color); diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp index be5ea0b7ab..ac4a01048e 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp @@ -149,13 +149,13 @@ int main(int argc, char *argv[]) while (true) { if (color_pointcloud) { rs.acquire(reinterpret_cast(I_color.bitmap), - reinterpret_cast(I_depth_raw.bitmap), &vp_pointcloud, pointcloud_color, NULL, - no_align ? NULL : &align_to); + reinterpret_cast(I_depth_raw.bitmap), &vp_pointcloud, pointcloud_color, nullptr, + no_align ? nullptr : &align_to); } else { rs.acquire(reinterpret_cast(I_color.bitmap), - reinterpret_cast(I_depth_raw.bitmap), &vp_pointcloud, pointcloud, NULL, - no_align ? NULL : &align_to); + reinterpret_cast(I_depth_raw.bitmap), &vp_pointcloud, pointcloud, nullptr, + no_align ? nullptr : &align_to); } vpImageConvert::createDepthHistogram(I_depth_raw, I_depth); diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp index 50b6005887..f4caef1ea4 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp @@ -193,13 +193,13 @@ int main(int argc, char *argv[]) if (pcl_color) { rs.acquire(reinterpret_cast(color.bitmap), reinterpret_cast(depth_raw.bitmap), - NULL, pointcloud_color, reinterpret_cast(infrared1.bitmap), - show_infrared2 ? reinterpret_cast(infrared2.bitmap) : NULL, NULL); + nullptr, pointcloud_color, reinterpret_cast(infrared1.bitmap), + show_infrared2 ? reinterpret_cast(infrared2.bitmap) : nullptr, nullptr); } else { rs.acquire(reinterpret_cast(color.bitmap), reinterpret_cast(depth_raw.bitmap), - NULL, pointcloud, reinterpret_cast(infrared1.bitmap), - show_infrared2 ? reinterpret_cast(infrared2.bitmap) : NULL, NULL); + nullptr, pointcloud, reinterpret_cast(infrared1.bitmap), + show_infrared2 ? reinterpret_cast(infrared2.bitmap) : nullptr, nullptr); } update_pointcloud = true; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp index 12cb8b1725..d4fb566e39 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp @@ -449,18 +449,18 @@ int main(int argc, char *argv[]) std::lock_guard lock(mutex); if (pcl_color) { - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud_color, + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, nullptr, pointcloud_color, (unsigned char *)infrared.bitmap); } else { - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud, + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, nullptr, pointcloud, (unsigned char *)infrared.bitmap); } update_pointcloud = true; } #else - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, + rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, nullptr, (unsigned char *)infrared.bitmap); #endif @@ -559,7 +559,7 @@ int main(int argc, char *argv[]) t_begin = vpTime::measureTimeMs(); while (vpTime::measureTimeMs() - t_begin < 10000) { double t = vpTime::measureTimeMs(); - rs.acquire(NULL, NULL, &pointcloud_colvector, NULL, NULL); + rs.acquire(nullptr, nullptr, &pointcloud_colvector, nullptr, nullptr); { std::lock_guard lock(mutex); diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp index 666d03f38c..5f84a4d420 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp @@ -86,7 +86,7 @@ int main() vpCameraParameters cam(300., 300., I_pose.getWidth() / 2, I_pose.getHeight() / 2); // For pose visualization - rs.acquire(&I_left, &I_right, &cMw_0, NULL, NULL, &confidence, &ts); + rs.acquire(&I_left, &I_right, &cMw_0, nullptr, nullptr, &confidence, &ts); #if defined(VISP_HAVE_X11) vpDisplayX display_left; // Left image diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp index c55622c7da..17f939e52c 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp @@ -69,7 +69,7 @@ int main() while (true) { - rs.getIMUData(&imu_acc, &imu_vel, NULL); + rs.getIMUData(&imu_acc, &imu_vel, nullptr); std::cout << "Gyro vel: x = " << std::setw(12) << imu_vel[0] << " y = " << std::setw(12) << imu_vel[1] << " z = " << std::setw(12) << imu_vel[2]; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp index cf38353a98..63053891bd 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp @@ -88,7 +88,7 @@ int main() display_pose.init(I_pose, 10, 10, "Pose visualizer"); #endif - confidence = rs.getOdometryData(&cMw_0, NULL, NULL, &ts); // Acquire first frame (pose only) + confidence = rs.getOdometryData(&cMw_0, nullptr, nullptr, &ts); // Acquire first frame (pose only) vpHomogeneousMatrix cextMc_0 = cextMw * cMw_0.inverse(); vpMeterPixelConversion::convertPoint(cam, cextMc_0[0][3] / cextMc_0[2][3], cextMc_0[1][3] / cextMc_0[2][3], @@ -97,7 +97,7 @@ int main() while (true) { double t = vpTime::measureTimeMs(); - confidence = rs.getOdometryData(&cMw, NULL, NULL, &ts); // Acquire timestamped pose only + confidence = rs.getOdometryData(&cMw, nullptr, nullptr, &ts); // Acquire timestamped pose only vpDisplay::display(I_pose); diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp index 516a700a2f..12d2d0b88b 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp @@ -105,7 +105,7 @@ int main() while (true) { double t = vpTime::measureTimeMs(); - rs.acquire(&I, NULL, NULL); // Acquire only left image + rs.acquire(&I, nullptr, nullptr); // Acquire only left image vpDisplay::display(I); diff --git a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp index 571de313f4..7388e378a4 100644 --- a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp @@ -290,24 +290,24 @@ void test_R200(vpRealSense &rs, const std::map &enables, if (direct_infrared_conversion) { if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); } else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); } } else { if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); } else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); } @@ -321,12 +321,12 @@ void test_R200(vpRealSense &rs, const std::map &enables, } else { if (direct_infrared_conversion) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); } else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); vpImageConvert::convert(infrared, I_infrared); diff --git a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp index 3a91cc5ed9..42bfb80d9b 100644 --- a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp @@ -267,22 +267,22 @@ void test_SR300(vpRealSense &rs, const std::map &enables, if (direct_infrared_conversion) { if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, - (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream); + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, + (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); } else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, - (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream); + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, + (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); } } else { if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, - (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream); + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, + (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); } else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, - (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream); + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, + (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); } vpImageConvert::convert(infrared, I_infrared); @@ -293,12 +293,12 @@ void test_SR300(vpRealSense &rs, const std::map &enables, } else { if (direct_infrared_conversion) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, - (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream); + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, + (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); } else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, - (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream); + rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, + (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); vpImageConvert::convert(infrared, I_infrared); } } @@ -480,7 +480,7 @@ int main(int argc, char *argv[]) double t_begin = vpTime::measureTimeMs(); while (true) { - rs.acquire(color_mat.data, NULL, NULL, infrared_mat.data); + rs.acquire(color_mat.data, nullptr, nullptr, infrared_mat.data); cv::imshow("Color mat", color_mat); cv::imshow("Infrared mat", infrared_mat); diff --git a/modules/tracker/blob/include/visp3/blob/vpDot2.h b/modules/tracker/blob/include/visp3/blob/vpDot2.h index a89dceba84..ec8171ebda 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot2.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot2.h @@ -361,7 +361,7 @@ class VISP_EXPORT vpDot2 : public vpTracker void track(const vpImage &I, vpImagePoint &cog, bool canMakeTheWindowGrow = true); static void trackAndDisplay(vpDot2 dot[], const unsigned int &n, vpImage &I, - std::vector &cogs, vpImagePoint *cogStar = NULL); + std::vector &cogs, vpImagePoint *cogStar = nullptr); #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS public: diff --git a/modules/tracker/blob/src/dots/vpDot2.cpp b/modules/tracker/blob/src/dots/vpDot2.cpp index f3453957db..4de44dbb60 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -1000,7 +1000,7 @@ void vpDot2::searchDotsInArea(const vpImage &I, int area_u, int a std::list::iterator itnice; std::list::iterator itbad; - vpDot2 *dotToTest = NULL; + vpDot2 *dotToTest = nullptr; vpDot2 tmpDot; unsigned int area_u_min = (unsigned int)area.getLeft(); @@ -1100,7 +1100,7 @@ void vpDot2::searchDotsInArea(const vpImage &I, int area_u, int a // otherwise estimate the width, height and surface of the dot we // created, and test it. - if (dotToTest != NULL) + if (dotToTest != nullptr) delete dotToTest; dotToTest = getInstance(); dotToTest->setCog(germ); @@ -1195,7 +1195,7 @@ void vpDot2::searchDotsInArea(const vpImage &I, int area_u, int a } } } - if (dotToTest != NULL) + if (dotToTest != nullptr) delete dotToTest; } @@ -2395,7 +2395,7 @@ vpMatrix vpDot2::defineDots(vpDot2 dot[], const unsigned int &n, const std::stri dots, will be displayed in green \param cogStar (optional) : array of - vpImagePoint indicating the desired position (default NULL), will be + vpImagePoint indicating the desired position (default nullptr), will be displayed in red */ void vpDot2::trackAndDisplay(vpDot2 dot[], const unsigned int &n, vpImage &I, @@ -2414,7 +2414,7 @@ void vpDot2::trackAndDisplay(vpDot2 dot[], const unsigned int &n, vpImage option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h b/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h index edce98a3a0..45e4dcc6a1 100644 --- a/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h +++ b/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h @@ -216,7 +216,7 @@ class VISP_EXPORT vpKltOpencv * * \param I : Grey level image used as input. This image should have only 1 channel. * \param mask : Image mask used to restrict the keypoint detection - * area. If mask is NULL, all the image will be considered. + * area. If mask is nullptr, all the image will be considered. * * \exception vpTrackingException::initializationError : If the image I is not * initialized, or if the image or the mask have bad coding format. diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h index 6d6a6be8fd..4ab137f519 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h @@ -328,7 +328,7 @@ class VISP_EXPORT vpMbEdgeKltTracker : protected: virtual void computeVVS(const vpImage &I, const unsigned int &nbInfos, unsigned int &nbrow, - unsigned int lvl = 0, double *edge_residual = NULL, double *klt_residual = NULL); + unsigned int lvl = 0, double *edge_residual = nullptr, double *klt_residual = nullptr); virtual void computeVVSInit() override; virtual void computeVVSInteractionMatrixAndResidu() override; using vpMbTracker::computeCovarianceMatrixVVS; diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h index bdd129c628..3175dcd0a1 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h @@ -764,10 +764,10 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void preTracking(const vpImage *const ptr_I, const pcl::PointCloud::ConstPtr &point_cloud); #endif - virtual void postTracking(const vpImage *const ptr_I = NULL, const unsigned int pointcloud_width = 0, + virtual void postTracking(const vpImage *const ptr_I = nullptr, const unsigned int pointcloud_width = 0, const unsigned int pointcloud_height = 0); - virtual void preTracking(const vpImage *const ptr_I = NULL, - const std::vector *const point_cloud = NULL, + virtual void preTracking(const vpImage *const ptr_I = nullptr, + const std::vector *const point_cloud = nullptr, const unsigned int pointcloud_width = 0, const unsigned int pointcloud_height = 0); virtual void reInitModel(const vpImage *const I, const vpImage *const I_color, diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h b/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h index 8edb9db333..38c233e647 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h @@ -293,25 +293,25 @@ vpMbHiddenFaces::vpMbHiddenFaces() : Lpol(), nbVisiblePolygon(0), s template vpMbHiddenFaces::~vpMbHiddenFaces() { for (unsigned int i = 0; i < Lpol.size(); i++) { - if (Lpol[i] != NULL) { + if (Lpol[i] != nullptr) { delete Lpol[i]; } - Lpol[i] = NULL; + Lpol[i] = nullptr; } Lpol.resize(0); #ifdef VISP_HAVE_OGRE - if (ogre != NULL) { + if (ogre != nullptr) { delete ogre; - ogre = NULL; + ogre = nullptr; } // This is already done by calling "delete ogre" // for(unsigned int i = 0 ; i < lOgrePolygons.size() ; i++){ - // if (lOgrePolygons[i]!=NULL){ + // if (lOgrePolygons[i]!=nullptr){ // delete lOgrePolygons[i]; // } - // lOgrePolygons[i] = NULL; + // lOgrePolygons[i] = nullptr; // } lOgrePolygons.resize(0); @@ -327,7 +327,7 @@ vpMbHiddenFaces::vpMbHiddenFaces(const vpMbHiddenFaces #ifdef VISP_HAVE_OGRE , ogreBackground(copy.ogreBackground), ogreInitialised(copy.ogreInitialised), nbRayAttempts(copy.nbRayAttempts), - ratioVisibleRay(copy.ratioVisibleRay), ogre(NULL), lOgrePolygons(), ogreShowConfigDialog(copy.ogreShowConfigDialog) + ratioVisibleRay(copy.ratioVisibleRay), ogre(nullptr), lOgrePolygons(), ogreShowConfigDialog(copy.ogreShowConfigDialog) #endif { // Copy the list of polygons @@ -393,25 +393,25 @@ template void vpMbHiddenFaces::reset() { nbVisiblePolygon = 0; for (unsigned int i = 0; i < Lpol.size(); i++) { - if (Lpol[i] != NULL) { + if (Lpol[i] != nullptr) { delete Lpol[i]; } - Lpol[i] = NULL; + Lpol[i] = nullptr; } Lpol.resize(0); #ifdef VISP_HAVE_OGRE - if (ogre != NULL) { + if (ogre != nullptr) { delete ogre; - ogre = NULL; + ogre = nullptr; } // This is already done by calling "delete ogre" // for(unsigned int i = 0 ; i < lOgrePolygons.size() ; i++){ - // if (lOgrePolygons[i]!=NULL){ + // if (lOgrePolygons[i]!=nullptr){ // delete lOgrePolygons[i]; // } - // lOgrePolygons[i] = NULL; + // lOgrePolygons[i] = nullptr; // } lOgrePolygons.resize(0); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h index 32949e7c1b..7d21b1216f 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h @@ -808,14 +808,14 @@ class VISP_EXPORT vpMbTracker virtual void computeVVSCheckLevenbergMarquardt(unsigned int iter, vpColVector &error, const vpColVector &m_error_prev, const vpHomogeneousMatrix &cMoPrev, double &mu, - bool &reStartFromLastIncrement, vpColVector *const w = NULL, - const vpColVector *const m_w_prev = NULL); + bool &reStartFromLastIncrement, vpColVector *const w = nullptr, + const vpColVector *const m_w_prev = nullptr); virtual void computeVVSInit() = 0; virtual void computeVVSInteractionMatrixAndResidu() = 0; virtual void computeVVSPoseEstimation(const bool isoJoIdentity, unsigned int iter, vpMatrix &L, vpMatrix <L, vpColVector &R, const vpColVector &error, vpColVector &error_prev, - vpColVector <R, double &mu, vpColVector &v, const vpColVector *const w = NULL, - vpColVector *const m_w_prev = NULL); + vpColVector <R, double &mu, vpColVector &v, const vpColVector *const w = nullptr, + vpColVector *const m_w_prev = nullptr); virtual void computeVVSWeights(vpRobust &robust, const vpColVector &error, vpColVector &w); #ifdef VISP_HAVE_COIN3D diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h index c462d2c406..1a2ed07bfe 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h @@ -104,11 +104,11 @@ class VISP_EXPORT vpMbtDistanceCircle // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpMbtDistanceCircle(const vpMbtDistanceCircle &) - // : name(), index(0), cam(), me(NULL), wmean(1), - // featureEllipse(), isTrackedCircle(true), meEllipse(NULL), - // circle(NULL), radius(0.), p1(NULL), p2(NULL), p3(NULL), + // : name(), index(0), cam(), me(nullptr), wmean(1), + // featureEllipse(), isTrackedCircle(true), meEllipse(nullptr), + // circle(nullptr), radius(0.), p1(nullptr), p2(nullptr), p3(nullptr), // L(), error(), nbFeature(0), Reinit(false), - // hiddenface(NULL), index_polygon(-1), isvisible(false) + // hiddenface(nullptr), index_polygon(-1), isvisible(false) // { // throw vpException(vpException::functionNotImplementedError, "Not // implemented!"); @@ -172,7 +172,7 @@ class VISP_EXPORT vpMbtDistanceCircle void initInteractionMatrixError(); bool initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, bool doNotTrack, - const vpImage *mask = NULL); + const vpImage *mask = nullptr); /*! Return if the circle is used for tracking. @@ -189,7 +189,7 @@ class VISP_EXPORT vpMbtDistanceCircle inline bool isVisible() const { return isvisible; } void reinitMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, - const vpImage *mask = NULL); + const vpImage *mask = nullptr); /*! Set the camera parameters. diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h index bb41a192ca..0e8787b932 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h @@ -118,12 +118,12 @@ class VISP_EXPORT vpMbtDistanceCylinder // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpMbtDistanceCylinder(const vpMbtDistanceCylinder &) - // : name(), index(0), cam(), me(NULL), wmean1(1), wmean2(1), + // : name(), index(0), cam(), me(nullptr), wmean1(1), wmean2(1), // featureline1(), featureline2(), isTrackedCylinder(true), - // meline1(NULL), meline2(NULL), cercle1(NULL), cercle2(NULL), - // radius(0), p1(NULL), p2(NULL), L(), error(), nbFeature(0), - // nbFeaturel1(0), nbFeaturel2(0), Reinit(false), c(NULL), - // hiddenface(NULL), index_polygon(-1), isvisible(false) + // meline1(nullptr), meline2(nullptr), cercle1(nullptr), cercle2(nullptr), + // radius(0), p1(nullptr), p2(nullptr), L(), error(), nbFeature(0), + // nbFeaturel1(0), nbFeaturel2(0), Reinit(false), c(nullptr), + // hiddenface(nullptr), index_polygon(-1), isvisible(false) // { // throw vpException(vpException::functionNotImplementedError, "Not // implemented!"); @@ -197,7 +197,7 @@ class VISP_EXPORT vpMbtDistanceCylinder void initInteractionMatrixError(); bool initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, bool doNotTrack, - const vpImage *mask = NULL); + const vpImage *mask = nullptr); /*! Return if the cylinder is used for tracking. @@ -214,7 +214,7 @@ class VISP_EXPORT vpMbtDistanceCylinder inline bool isVisible() const { return isvisible; } void reinitMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, - const vpImage *mask = NULL); + const vpImage *mask = nullptr); /*! Set the camera parameters. diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h index 5530f493df..f8ac56233c 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h @@ -117,7 +117,7 @@ class VISP_EXPORT vpMbtDistanceKltCylinder // initPoints(), initPoints3D(), curPoints(), curPointsInd(), // nbPointsCur(0), nbPointsInit(0), minNbPoint(4), // enoughPoints(false), cam(), isTrackedKltCylinder(true), - // listIndicesCylinderBBox(), hiddenface(NULL), useScanLine(false) + // listIndicesCylinderBBox(), hiddenface(nullptr), useScanLine(false) // { // throw vpException(vpException::functionNotImplementedError, "Not // implemented!"); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h index bc20dfb94a..16c69ae071 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h @@ -117,7 +117,7 @@ class VISP_EXPORT vpMbtDistanceKltPoints // curPoints(), curPointsInd(), // nbPointsCur(0), nbPointsInit(0), minNbPoint(4), // enoughPoints(false), dt(1.), d0(1.), cam(), - // isTrackedKltPoints(true), polygon(NULL), hiddenface(NULL), + // isTrackedKltPoints(true), polygon(nullptr), hiddenface(nullptr), // useScanLine(false) // { // throw vpException(vpException::functionNotImplementedError, "Not @@ -133,7 +133,7 @@ class VISP_EXPORT vpMbtDistanceKltPoints vpMbtDistanceKltPoints(); virtual ~vpMbtDistanceKltPoints(); - unsigned int computeNbDetectedCurrent(const vpKltOpencv &_tracker, const vpImage *mask = NULL); + unsigned int computeNbDetectedCurrent(const vpKltOpencv &_tracker, const vpImage *mask = nullptr); void computeHomography(const vpHomogeneousMatrix &_cTc0, vpHomography &cHc0); void computeInteractionMatrixAndResidu(vpColVector &_R, vpMatrix &_J); @@ -185,7 +185,7 @@ class VISP_EXPORT vpMbtDistanceKltPoints inline bool hasEnoughPoints() const { return enoughPoints; } - void init(const vpKltOpencv &_tracker, const vpImage *mask = NULL); + void init(const vpKltOpencv &_tracker, const vpImage *mask = nullptr); /*! Return if the klt points are used for tracking. diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h index 831078713d..ac64ea07dc 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h @@ -112,11 +112,11 @@ class VISP_EXPORT vpMbtDistanceLine // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpMbtDistanceLine(const vpMbtDistanceLine &) - // : name(), index(0), cam(), me(NULL), isTrackedLine(true), + // : name(), index(0), cam(), me(nullptr), isTrackedLine(true), // isTrackedLineWithVisibility(true), // wmean(1), featureline(), poly(), useScanLine(false), meline(), - // line(NULL), p1(NULL), p2(NULL), L(), error(), nbFeature(), - // nbFeatureTotal(0), Reinit(false), hiddenface(NULL), + // line(nullptr), p1(nullptr), p2(nullptr), L(), error(), nbFeature(), + // nbFeatureTotal(0), Reinit(false), hiddenface(nullptr), // Lindex_polygon(), Lindex_polygon_tracked(), isvisible(false) // { // throw vpException(vpException::functionNotImplementedError, "Not @@ -192,7 +192,7 @@ class VISP_EXPORT vpMbtDistanceLine void initInteractionMatrixError(); bool initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, bool doNotTrack, - const vpImage *mask = NULL); + const vpImage *mask = nullptr); /*! Return if the line is used for tracking. @@ -209,7 +209,7 @@ class VISP_EXPORT vpMbtDistanceLine inline bool isVisible() const { return isvisible; } void reinitMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, - const vpImage *mask = NULL); + const vpImage *mask = nullptr); /*! Set the camera parameters. diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h index 5d0fc4d69f..0ae0eea302 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h @@ -96,7 +96,7 @@ class VISP_EXPORT vpMbtFaceDepthDense vpImage &debugImage, std::vector > &roiPts_vec #endif , - const vpImage *mask = NULL); + const vpImage *mask = nullptr); #endif bool computeDesiredFeatures(const vpHomogeneousMatrix &cMo, unsigned int width, unsigned int height, const std::vector &point_cloud, unsigned int stepX, unsigned int stepY @@ -105,7 +105,7 @@ class VISP_EXPORT vpMbtFaceDepthDense vpImage &debugImage, std::vector > &roiPts_vec #endif , - const vpImage *mask = NULL); + const vpImage *mask = nullptr); void computeInteractionMatrixAndResidu(const vpHomogeneousMatrix &cMo, vpMatrix &L, vpColVector &error); @@ -168,10 +168,10 @@ class VISP_EXPORT vpMbtFaceDepthDense //! The second extremity clipped in the image frame vpImagePoint m_imPt2; - PolygonLine() : m_p1(NULL), m_p2(NULL), m_poly(), m_imPt1(), m_imPt2() {} + PolygonLine() : m_p1(nullptr), m_p2(nullptr), m_poly(), m_imPt1(), m_imPt2() {} PolygonLine(const PolygonLine &polyLine) - : m_p1(NULL), m_p2(NULL), m_poly(polyLine.m_poly), m_imPt1(polyLine.m_imPt1), m_imPt2(polyLine.m_imPt2) + : m_p1(nullptr), m_p2(nullptr), m_poly(polyLine.m_poly), m_imPt1(polyLine.m_imPt1), m_imPt2(polyLine.m_imPt2) { m_p1 = &m_poly.p[0]; m_p2 = &m_poly.p[1]; diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h index 61cd959aea..db5a673d70 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h @@ -98,7 +98,7 @@ class VISP_EXPORT vpMbtFaceDepthNormal vpImage &debugImage, std::vector > &roiPts_vec #endif , - const vpImage *mask = NULL); + const vpImage *mask = nullptr); #endif bool computeDesiredFeatures(const vpHomogeneousMatrix &cMo, unsigned int width, unsigned int height, const std::vector &point_cloud, vpColVector &desired_features, @@ -108,7 +108,7 @@ class VISP_EXPORT vpMbtFaceDepthNormal vpImage &debugImage, std::vector > &roiPts_vec #endif , - const vpImage *mask = NULL); + const vpImage *mask = nullptr); void computeInteractionMatrix(const vpHomogeneousMatrix &cMo, vpMatrix &L, vpColVector &features); @@ -179,10 +179,10 @@ class VISP_EXPORT vpMbtFaceDepthNormal //! The second extremity clipped in the image frame vpImagePoint m_imPt2; - PolygonLine() : m_p1(NULL), m_p2(NULL), m_poly(), m_imPt1(), m_imPt2() {} + PolygonLine() : m_p1(nullptr), m_p2(nullptr), m_poly(), m_imPt1(), m_imPt2() {} PolygonLine(const PolygonLine &polyLine) - : m_p1(NULL), m_p2(NULL), m_poly(polyLine.m_poly), m_imPt1(polyLine.m_imPt1), m_imPt2(polyLine.m_imPt2) + : m_p1(nullptr), m_p2(nullptr), m_poly(polyLine.m_poly), m_imPt1(polyLine.m_imPt1), m_imPt2(polyLine.m_imPt2) { m_p1 = &m_poly.p[0]; m_p2 = &m_poly.p[1]; diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h index 2a712dc9d4..f5fd18fa99 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h @@ -66,7 +66,7 @@ class VISP_EXPORT vpMbtMeEllipse : public vpMeEllipse unsigned int thickness); void initTracking(const vpImage &I, const vpImagePoint &ic, double n20_p, double n11_p, double n02_p, - bool doNotTrack, vpImagePoint *pt1 = NULL, const vpImagePoint *pt2 = NULL); + bool doNotTrack, vpImagePoint *pt1 = nullptr, const vpImagePoint *pt2 = nullptr); void track(const vpImage &I); void updateParameters(const vpImage &I, const vpImagePoint ¢er_p, double n20_p, double n11_p, diff --git a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp index 63693eaa1d..ca74cdc202 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp @@ -58,7 +58,7 @@ vpMbDepthDenseTracker::vpMbDepthDenseTracker() m_robust_depthDense(), m_w_depthDense(), m_weightedError_depthDense() #if DEBUG_DISPLAY_DEPTH_DENSE , - m_debugDisp_depthDense(NULL), m_debugImage_depthDense() + m_debugDisp_depthDense(nullptr), m_debugImage_depthDense() #endif { #ifdef VISP_HAVE_OGRE @@ -439,7 +439,7 @@ void vpMbDepthDenseTracker::reInitModel(const vpImage &I, const s for (size_t i = 0; i < m_depthDenseFaces.size(); i++) { delete m_depthDenseFaces[i]; - m_depthDenseFaces[i] = NULL; + m_depthDenseFaces[i] = nullptr; } m_depthDenseFaces.clear(); @@ -466,7 +466,7 @@ void vpMbDepthDenseTracker::resetTracker() ++it) { vpMbtFaceDepthDense *normal_face = *it; delete normal_face; - normal_face = NULL; + normal_face = nullptr; } m_depthDenseFaces.clear(); diff --git a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp index 651ce4b7cf..0901245fca 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp @@ -61,7 +61,7 @@ vpMbDepthNormalTracker::vpMbDepthNormalTracker() m_robust_depthNormal(), m_w_depthNormal(), m_weightedError_depthNormal() #if DEBUG_DISPLAY_DEPTH_NORMAL , - m_debugDisp_depthNormal(NULL), m_debugImage_depthNormal() + m_debugDisp_depthNormal(nullptr), m_debugImage_depthNormal() #endif { #ifdef VISP_HAVE_OGRE @@ -476,7 +476,7 @@ void vpMbDepthNormalTracker::reInitModel(const vpImage &I, const for (size_t i = 0; i < m_depthNormalFaces.size(); i++) { delete m_depthNormalFaces[i]; - m_depthNormalFaces[i] = NULL; + m_depthNormalFaces[i] = nullptr; } m_depthNormalFaces.clear(); @@ -503,7 +503,7 @@ void vpMbDepthNormalTracker::resetTracker() ++it) { vpMbtFaceDepthNormal *normal_face = *it; delete normal_face; - normal_face = NULL; + normal_face = nullptr; } m_depthNormalFaces.clear(); diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp index 07f25e06cd..0dacb833f1 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp @@ -156,8 +156,8 @@ inline float64x2_t v_fma(const float64x2_t &a, const float64x2_t &b, const float #endif // !USE_OPENCV_HAL && (USE_SSE || USE_NEON) vpMbtFaceDepthDense::vpMbtFaceDepthDense() - : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(NULL), - m_planeObject(), m_polygon(NULL), m_useScanLine(false), + : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(nullptr), + m_planeObject(), m_polygon(nullptr), m_useScanLine(false), m_depthDenseFilteringMethod(DEPTH_OCCUPANCY_RATIO_FILTERING), m_depthDenseFilteringMaxDist(3.0), m_depthDenseFilteringMinDist(0.8), m_depthDenseFilteringOccupancyRatio(0.3), m_isTrackedDepthDenseFace(true), m_isVisible(false), m_listOfFaceLines(), m_planeCamera(), m_pointCloudFace(), m_polygonLines() diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index d2c7390ac7..faee1d75d3 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -56,8 +56,8 @@ #endif vpMbtFaceDepthNormal::vpMbtFaceDepthNormal() - : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(NULL), - m_planeObject(), m_polygon(NULL), m_useScanLine(false), m_faceActivated(false), + : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(nullptr), + m_planeObject(), m_polygon(nullptr), m_useScanLine(false), m_faceActivated(false), m_faceCentroidMethod(GEOMETRIC_CENTROID), m_faceDesiredCentroid(), m_faceDesiredNormal(), m_featureEstimationMethod(ROBUST_FEATURE_ESTIMATION), m_isTrackedDepthNormalFace(true), m_isVisible(false), m_listOfFaceLines(), m_planeCamera(), diff --git a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp index d4d7ae9f47..663fa223f0 100644 --- a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp +++ b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp @@ -88,27 +88,27 @@ vpMbEdgeTracker::~vpMbEdgeTracker() if (scales[i]) { for (std::list::const_iterator it = lines[i].begin(); it != lines[i].end(); ++it) { l = *it; - if (l != NULL) { + if (l != nullptr) { delete l; } - l = NULL; + l = nullptr; } for (std::list::const_iterator it = cylinders[i].begin(); it != cylinders[i].end(); ++it) { cy = *it; - if (cy != NULL) { + if (cy != nullptr) { delete cy; } - cy = NULL; + cy = nullptr; } for (std::list::const_iterator it = circles[i].begin(); it != circles[i].end(); ++it) { ci = *it; - if (ci != NULL) { + if (ci != nullptr) { delete ci; } - ci = NULL; + ci = nullptr; } lines[i].clear(); @@ -323,7 +323,7 @@ void vpMbEdgeTracker::computeVVSFirstPhase(const vpImage &_I, uns unsigned int indexFeature = 0; for (size_t a = 0; a < l->meline.size(); a++) { - if (iter == 0 && l->meline[a] != NULL) + if (iter == 0 && l->meline[a] != nullptr) itListLine = l->meline[a]->getMeList().begin(); for (unsigned int i = 0; i < l->nbFeature[a]; i++) { @@ -393,7 +393,7 @@ void vpMbEdgeTracker::computeVVSFirstPhase(const vpImage &_I, uns std::list::const_iterator itCyl1; std::list::const_iterator itCyl2; - if (iter == 0 && (cy->meline1 != NULL || cy->meline2 != NULL)) { + if (iter == 0 && (cy->meline1 != nullptr || cy->meline2 != nullptr)) { itCyl1 = cy->meline1->getMeList().begin(); itCyl2 = cy->meline2->getMeList().begin(); } @@ -486,7 +486,7 @@ void vpMbEdgeTracker::computeVVSFirstPhase(const vpImage &_I, uns double fac = 1.0; std::list::const_iterator itCir; - if (iter == 0 && (ci->meEllipse != NULL)) { + if (iter == 0 && (ci->meEllipse != nullptr)) { itCir = ci->meEllipse->getMeList().begin(); } @@ -576,7 +576,7 @@ void vpMbEdgeTracker::computeVVSFirstPhaseFactor(const vpImage &I for (size_t a = 0; a < l->meline.size(); a++) { std::list::const_iterator itListLine; - if (l->meline[a] != NULL) { + if (l->meline[a] != nullptr) { itListLine = l->meline[a]->getMeList().begin(); for (unsigned int i = 0; i < l->nbFeature[a]; i++) { @@ -600,7 +600,7 @@ void vpMbEdgeTracker::computeVVSFirstPhaseFactor(const vpImage &I std::list::const_iterator itCyl1; std::list::const_iterator itCyl2; - if ((cy->meline1 != NULL || cy->meline2 != NULL)) { + if ((cy->meline1 != nullptr || cy->meline2 != nullptr)) { itCyl1 = cy->meline1->getMeList().begin(); itCyl2 = cy->meline2->getMeList().begin(); @@ -629,7 +629,7 @@ void vpMbEdgeTracker::computeVVSFirstPhaseFactor(const vpImage &I ci->computeInteractionMatrixError(m_cMo); std::list::const_iterator itCir; - if (ci->meEllipse != NULL) { + if (ci->meEllipse != nullptr) { itCir = ci->meEllipse->getMeList().begin(); double fac = 1.0; @@ -861,7 +861,7 @@ void vpMbEdgeTracker::computeProjectionError(const vpImage &_I) vpMbtDistanceLine *l = *it; if (l->isVisible() && l->isTracked()) { for (size_t a = 0; a < l->meline.size(); a++) { - if (l->meline[a] != NULL) { + if (l->meline[a] != nullptr) { double lineNormGradient; unsigned int lineNbFeatures; l->meline[a]->computeProjectionError(_I, lineNormGradient, lineNbFeatures, m_SobelX, m_SobelY, @@ -878,7 +878,7 @@ void vpMbEdgeTracker::computeProjectionError(const vpImage &_I) it != cylinders[scaleLevel].end(); ++it) { vpMbtDistanceCylinder *cy = *it; if (cy->isVisible() && cy->isTracked()) { - if (cy->meline1 != NULL) { + if (cy->meline1 != nullptr) { double cylinderNormGradient = 0; unsigned int cylinderNbFeatures = 0; cy->meline1->computeProjectionError(_I, cylinderNormGradient, cylinderNbFeatures, m_SobelX, m_SobelY, @@ -888,7 +888,7 @@ void vpMbEdgeTracker::computeProjectionError(const vpImage &_I) nbFeatures += cylinderNbFeatures; } - if (cy->meline2 != NULL) { + if (cy->meline2 != nullptr) { double cylinderNormGradient = 0; unsigned int cylinderNbFeatures = 0; cy->meline2->computeProjectionError(_I, cylinderNormGradient, cylinderNbFeatures, m_SobelX, m_SobelY, @@ -903,7 +903,7 @@ void vpMbEdgeTracker::computeProjectionError(const vpImage &_I) for (std::list::const_iterator it = circles[scaleLevel].begin(); it != circles[scaleLevel].end(); ++it) { vpMbtDistanceCircle *c = *it; - if (c->isVisible() && c->isTracked() && c->meEllipse != NULL) { + if (c->isVisible() && c->isTracked() && c->meEllipse != nullptr) { double circleNormGradient = 0; unsigned int circleNbFeatures = 0; c->meEllipse->computeProjectionError(_I, circleNormGradient, circleNbFeatures, m_SobelX, m_SobelY, @@ -940,7 +940,7 @@ void vpMbEdgeTracker::testTracking() vpMbtDistanceLine *l = *it; if (l->isVisible() && l->isTracked()) { for (size_t a = 0; a < l->meline.size(); a++) { - if (l->meline[a] != NULL) { + if (l->meline[a] != nullptr) { nbExpectedPoint += (int)l->meline[a]->expecteddensity; for (std::list::const_iterator itme = l->meline[a]->getMeList().begin(); itme != l->meline[a]->getMeList().end(); ++itme) { @@ -958,7 +958,7 @@ void vpMbEdgeTracker::testTracking() for (std::list::const_iterator it = cylinders[scaleLevel].begin(); it != cylinders[scaleLevel].end(); ++it) { vpMbtDistanceCylinder *cy = *it; - if ((cy->meline1 != NULL && cy->meline2 != NULL) && cy->isVisible() && cy->isTracked()) { + if ((cy->meline1 != nullptr && cy->meline2 != nullptr) && cy->isVisible() && cy->isTracked()) { nbExpectedPoint += (int)cy->meline1->expecteddensity; for (std::list::const_iterator itme1 = cy->meline1->getMeList().begin(); itme1 != cy->meline1->getMeList().end(); ++itme1) { @@ -983,7 +983,7 @@ void vpMbEdgeTracker::testTracking() for (std::list::const_iterator it = circles[scaleLevel].begin(); it != circles[scaleLevel].end(); ++it) { vpMbtDistanceCircle *ci = *it; - if (ci->isVisible() && ci->isTracked() && ci->meEllipse != NULL) { + if (ci->isVisible() && ci->isTracked() && ci->meEllipse != nullptr) { nbExpectedPoint += ci->meEllipse->getExpectedDensity(); for (std::list::const_iterator itme = ci->meEllipse->getMeList().begin(); itme != ci->meEllipse->getMeList().end(); ++itme) { @@ -1545,7 +1545,7 @@ void vpMbEdgeTracker::initMovingEdge(const vpImage &I, const vpHo } else { l->setVisible(false); for (size_t a = 0; a < l->meline.size(); a++) { - if (l->meline[a] != NULL) + if (l->meline[a] != nullptr) delete l->meline[a]; if (a < l->nbFeature.size()) l->nbFeature[a] = 0; @@ -1574,18 +1574,18 @@ void vpMbEdgeTracker::initMovingEdge(const vpImage &I, const vpHo if (isvisible) { cy->setVisible(true); - if (cy->meline1 == NULL || cy->meline2 == NULL) { + if (cy->meline1 == nullptr || cy->meline2 == nullptr) { if (cy->isTracked()) cy->initMovingEdge(I, _cMo, doNotTrack, m_mask); } } else { cy->setVisible(false); - if (cy->meline1 != NULL) + if (cy->meline1 != nullptr) delete cy->meline1; - if (cy->meline2 != NULL) + if (cy->meline2 != nullptr) delete cy->meline2; - cy->meline1 = NULL; - cy->meline2 = NULL; + cy->meline1 = nullptr; + cy->meline2 = nullptr; cy->nbFeature = 0; cy->nbFeaturel1 = 0; cy->nbFeaturel2 = 0; @@ -1607,15 +1607,15 @@ void vpMbEdgeTracker::initMovingEdge(const vpImage &I, const vpHo if (isvisible) { ci->setVisible(true); - if (ci->meEllipse == NULL) { + if (ci->meEllipse == nullptr) { if (ci->isTracked()) ci->initMovingEdge(I, _cMo, doNotTrack, m_mask); } } else { ci->setVisible(false); - if (ci->meEllipse != NULL) + if (ci->meEllipse != nullptr) delete ci->meEllipse; - ci->meEllipse = NULL; + ci->meEllipse = nullptr; ci->nbFeature = 0; } } @@ -1645,7 +1645,7 @@ void vpMbEdgeTracker::trackMovingEdge(const vpImage &I) it != cylinders[scaleLevel].end(); ++it) { vpMbtDistanceCylinder *cy = *it; if (cy->isVisible() && cy->isTracked()) { - if (cy->meline1 == NULL || cy->meline2 == NULL) { + if (cy->meline1 == nullptr || cy->meline2 == nullptr) { cy->initMovingEdge(I, m_cMo, doNotTrack, m_mask); } cy->trackMovingEdge(I, m_cMo); @@ -1656,7 +1656,7 @@ void vpMbEdgeTracker::trackMovingEdge(const vpImage &I) it != circles[scaleLevel].end(); ++it) { vpMbtDistanceCircle *ci = *it; if (ci->isVisible() && ci->isTracked()) { - if (ci->meEllipse == NULL) { + if (ci->meEllipse == nullptr) { ci->initMovingEdge(I, m_cMo, doNotTrack, m_mask); } ci->trackMovingEdge(I, m_cMo); @@ -1911,9 +1911,9 @@ void vpMbEdgeTracker::resetMovingEdge() if (scales[i]) { for (std::list::const_iterator it = lines[i].begin(); it != lines[i].end(); ++it) { for (size_t a = 0; a < (*it)->meline.size(); a++) { - if ((*it)->meline[a] != NULL) { + if ((*it)->meline[a] != nullptr) { delete (*it)->meline[a]; - (*it)->meline[a] = NULL; + (*it)->meline[a] = nullptr; } } @@ -1924,13 +1924,13 @@ void vpMbEdgeTracker::resetMovingEdge() for (std::list::const_iterator it = cylinders[i].begin(); it != cylinders[i].end(); ++it) { - if ((*it)->meline1 != NULL) { + if ((*it)->meline1 != nullptr) { delete (*it)->meline1; - (*it)->meline1 = NULL; + (*it)->meline1 = nullptr; } - if ((*it)->meline2 != NULL) { + if ((*it)->meline2 != nullptr) { delete (*it)->meline2; - (*it)->meline2 = NULL; + (*it)->meline2 = nullptr; } (*it)->nbFeature = 0; @@ -1939,9 +1939,9 @@ void vpMbEdgeTracker::resetMovingEdge() } for (std::list::const_iterator it = circles[i].begin(); it != circles[i].end(); ++it) { - if ((*it)->meEllipse != NULL) { + if ((*it)->meEllipse != nullptr) { delete (*it)->meEllipse; - (*it)->meEllipse = NULL; + (*it)->meEllipse = nullptr; } (*it)->nbFeature = 0; } @@ -2379,24 +2379,24 @@ void vpMbEdgeTracker::resetTracker() if (scales[i]) { for (std::list::const_iterator it = lines[i].begin(); it != lines[i].end(); ++it) { l = *it; - if (l != NULL) + if (l != nullptr) delete l; - l = NULL; + l = nullptr; } for (std::list::const_iterator it = cylinders[i].begin(); it != cylinders[i].end(); ++it) { cy = *it; - if (cy != NULL) + if (cy != nullptr) delete cy; - cy = NULL; + cy = nullptr; } for (std::list::const_iterator it = circles[i].begin(); it != circles[i].end(); ++it) { ci = *it; - if (ci != NULL) + if (ci != nullptr) delete ci; - ci = NULL; + ci = nullptr; } lines[i].clear(); cylinders[i].clear(); @@ -2453,24 +2453,24 @@ void vpMbEdgeTracker::reInitModel(const vpImage &I, const std::st if (scales[i]) { for (std::list::const_iterator it = lines[i].begin(); it != lines[i].end(); ++it) { l = *it; - if (l != NULL) + if (l != nullptr) delete l; - l = NULL; + l = nullptr; } for (std::list::const_iterator it = cylinders[i].begin(); it != cylinders[i].end(); ++it) { cy = *it; - if (cy != NULL) + if (cy != nullptr) delete cy; - cy = NULL; + cy = nullptr; } for (std::list::const_iterator it = circles[i].begin(); it != circles[i].end(); ++it) { ci = *it; - if (ci != NULL) + if (ci != nullptr) delete ci; - ci = NULL; + ci = nullptr; } lines[i].clear(); @@ -2529,7 +2529,7 @@ unsigned int vpMbEdgeTracker::getNbPoints(unsigned int level) const for (std::list::const_iterator it = cylinders[level].begin(); it != cylinders[level].end(); ++it) { cy = *it; - if (cy->isVisible() && cy->isTracked() && (cy->meline1 != NULL || cy->meline2 != NULL)) { + if (cy->isVisible() && cy->isTracked() && (cy->meline1 != nullptr || cy->meline2 != nullptr)) { for (std::list::const_iterator itme1 = cy->meline1->getMeList().begin(); itme1 != cy->meline1->getMeList().end(); ++itme1) { if (itme1->getState() == vpMeSite::NO_SUPPRESSION) @@ -2546,7 +2546,7 @@ unsigned int vpMbEdgeTracker::getNbPoints(unsigned int level) const vpMbtDistanceCircle *ci; for (std::list::const_iterator it = circles[level].begin(); it != circles[level].end(); ++it) { ci = *it; - if (ci->isVisible() && ci->isTracked() && ci->meEllipse != NULL) { + if (ci->isVisible() && ci->isTracked() && ci->meEllipse != nullptr) { for (std::list::const_iterator itme = ci->meEllipse->getMeList().begin(); itme != ci->meEllipse->getMeList().end(); ++itme) { if (itme->getState() == vpMeSite::NO_SUPPRESSION) @@ -2723,7 +2723,7 @@ void vpMbEdgeTracker::initPyramid(const vpImage &_I, if (scales[0]) { _pyramid[0] = &_I; } else { - _pyramid[0] = NULL; + _pyramid[0] = nullptr; } for (unsigned int i = 1; i < _pyramid.size(); i += 1) { @@ -2737,7 +2737,7 @@ void vpMbEdgeTracker::initPyramid(const vpImage &_I, } _pyramid[i] = I; } else { - _pyramid[i] = NULL; + _pyramid[i] = nullptr; } } } @@ -2751,11 +2751,11 @@ void vpMbEdgeTracker::initPyramid(const vpImage &_I, void vpMbEdgeTracker::cleanPyramid(std::vector *> &_pyramid) { if (_pyramid.size() > 0) { - _pyramid[0] = NULL; + _pyramid[0] = nullptr; for (unsigned int i = 1; i < _pyramid.size(); i += 1) { - if (_pyramid[i] != NULL) { + if (_pyramid[i] != nullptr) { delete _pyramid[i]; - _pyramid[i] = NULL; + _pyramid[i] = nullptr; } } _pyramid.resize(0); diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp index e85a72d168..5bfffe2fb7 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp @@ -56,8 +56,8 @@ Basic constructor */ vpMbtDistanceCircle::vpMbtDistanceCircle() - : name(), index(0), cam(), me(NULL), wmean(1), featureEllipse(), isTrackedCircle(true), meEllipse(NULL), circle(NULL), - radius(0.), p1(NULL), p2(NULL), p3(NULL), L(), error(), nbFeature(0), Reinit(false), hiddenface(NULL), + : name(), index(0), cam(), me(nullptr), wmean(1), featureEllipse(), isTrackedCircle(true), meEllipse(nullptr), circle(nullptr), + radius(0.), p1(nullptr), p2(nullptr), p3(nullptr), L(), error(), nbFeature(0), Reinit(false), hiddenface(nullptr), index_polygon(-1), isvisible(false) { } @@ -66,15 +66,15 @@ vpMbtDistanceCircle::vpMbtDistanceCircle() */ vpMbtDistanceCircle::~vpMbtDistanceCircle() { - if (meEllipse != NULL) + if (meEllipse != nullptr) delete meEllipse; - if (circle != NULL) + if (circle != nullptr) delete circle; - if (p1 != NULL) + if (p1 != nullptr) delete p1; - if (p2 != NULL) + if (p2 != nullptr) delete p2; - if (p3 != NULL) + if (p3 != nullptr) delete p3; } @@ -125,7 +125,7 @@ void vpMbtDistanceCircle::buildFrom(const vpPoint &_p1, const vpPoint &_p2, cons void vpMbtDistanceCircle::setMovingEdge(vpMe *_me) { me = _me; - if (meEllipse != NULL) { + if (meEllipse != nullptr) { meEllipse->setMe(me); } } @@ -138,7 +138,7 @@ void vpMbtDistanceCircle::setMovingEdge(vpMe *_me) \param I : The image. \param cMo : The pose of the camera used to initialize the moving edges. \param doNotTrack : If true, ME are not tracked. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. \return false if an error occur, true otherwise. */ bool vpMbtDistanceCircle::initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, @@ -244,16 +244,16 @@ void vpMbtDistanceCircle::updateMovingEdge(const vpImage &I, cons \param I : the image. \param cMo : The pose of the camera. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. */ void vpMbtDistanceCircle::reinitMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpImage *mask) { - if (meEllipse != NULL) + if (meEllipse != nullptr) delete meEllipse; - meEllipse = NULL; + meEllipse = nullptr; if (!initMovingEdge(I, cMo, false, mask)) Reinit = true; @@ -317,7 +317,7 @@ std::vector > vpMbtDistanceCircle::getFeaturesForDisplay() { std::vector > features; - if (meEllipse != NULL) { + if (meEllipse != nullptr) { for (std::list::const_iterator it = meEllipse->getMeList().begin(); it != meEllipse->getMeList().end(); ++it) { vpMeSite p_me = *it; @@ -385,7 +385,7 @@ std::vector vpMbtDistanceCircle::getModelForDisplay(const vpHomogeneousM */ void vpMbtDistanceCircle::displayMovingEdges(const vpImage &I) { - if (meEllipse != NULL) { + if (meEllipse != nullptr) { meEllipse->display(I); // display the me if (vpDEBUG_ENABLE(3)) vpDisplay::flush(I); @@ -394,7 +394,7 @@ void vpMbtDistanceCircle::displayMovingEdges(const vpImage &I) void vpMbtDistanceCircle::displayMovingEdges(const vpImage &I) { - if (meEllipse != NULL) { + if (meEllipse != nullptr) { meEllipse->display(I); // display the me if (vpDEBUG_ENABLE(3)) vpDisplay::flush(I); diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp index 9ba91189f4..ba13ab1220 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp @@ -60,9 +60,9 @@ Basic constructor */ vpMbtDistanceCylinder::vpMbtDistanceCylinder() - : name(), index(0), cam(), me(NULL), wmean1(1), wmean2(1), featureline1(), featureline2(), isTrackedCylinder(true), - meline1(NULL), meline2(NULL), cercle1(NULL), cercle2(NULL), radius(0), p1(NULL), p2(NULL), L(), error(), - nbFeature(0), nbFeaturel1(0), nbFeaturel2(0), Reinit(false), c(NULL), hiddenface(NULL), index_polygon(-1), + : name(), index(0), cam(), me(nullptr), wmean1(1), wmean2(1), featureline1(), featureline2(), isTrackedCylinder(true), + meline1(nullptr), meline2(nullptr), cercle1(nullptr), cercle2(nullptr), radius(0), p1(nullptr), p2(nullptr), L(), error(), + nbFeature(0), nbFeaturel1(0), nbFeaturel2(0), Reinit(false), c(nullptr), hiddenface(nullptr), index_polygon(-1), isvisible(false) { } @@ -71,19 +71,19 @@ vpMbtDistanceCylinder::vpMbtDistanceCylinder() */ vpMbtDistanceCylinder::~vpMbtDistanceCylinder() { - if (p1 != NULL) + if (p1 != nullptr) delete p1; - if (p2 != NULL) + if (p2 != nullptr) delete p2; - if (c != NULL) + if (c != nullptr) delete c; - if (meline1 != NULL) + if (meline1 != nullptr) delete meline1; - if (meline2 != NULL) + if (meline2 != nullptr) delete meline2; - if (cercle1 != NULL) + if (cercle1 != nullptr) delete cercle1; - if (cercle2 != NULL) + if (cercle2 != nullptr) delete cercle2; } @@ -157,10 +157,10 @@ void vpMbtDistanceCylinder::buildFrom(const vpPoint &_p1, const vpPoint &_p2, do void vpMbtDistanceCylinder::setMovingEdge(vpMe *_me) { me = _me; - if (meline1 != NULL) { + if (meline1 != nullptr) { meline1->setMe(me); } - if (meline2 != NULL) { + if (meline2 != nullptr) { meline2->setMe(me); } } @@ -173,7 +173,7 @@ void vpMbtDistanceCylinder::setMovingEdge(vpMe *_me) \param I : The image. \param cMo : The pose of the camera used to initialize the moving edges. \param doNotTrack : If true, ME are not tracked. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. \return false if an error occur, true otherwise. */ bool vpMbtDistanceCylinder::initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, @@ -497,19 +497,19 @@ void vpMbtDistanceCylinder::updateMovingEdge(const vpImage &I, co \param I : the image. \param cMo : The pose of the camera. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. */ void vpMbtDistanceCylinder::reinitMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpImage *mask) { - if (meline1 != NULL) + if (meline1 != nullptr) delete meline1; - if (meline2 != NULL) + if (meline2 != nullptr) delete meline2; - meline1 = NULL; - meline2 = NULL; + meline1 = nullptr; + meline2 = nullptr; if (!initMovingEdge(I, cMo, false, mask)) Reinit = true; @@ -575,7 +575,7 @@ std::vector > vpMbtDistanceCylinder::getFeaturesForDisplay() { std::vector > features; - if (meline1 != NULL) { + if (meline1 != nullptr) { for (std::list::const_iterator it = meline1->getMeList().begin(); it != meline1->getMeList().end(); ++it) { vpMeSite p_me = *it; @@ -586,7 +586,7 @@ std::vector > vpMbtDistanceCylinder::getFeaturesForDisplay() } } - if (meline2 != NULL) { + if (meline2 != nullptr) { for (std::list::const_iterator it = meline2->getMeList().begin(); it != meline2->getMeList().end(); ++it) { vpMeSite p_me = *it; @@ -691,20 +691,20 @@ std::vector > vpMbtDistanceCylinder::getModelForDisplay(unsi */ void vpMbtDistanceCylinder::displayMovingEdges(const vpImage &I) { - if (meline1 != NULL) { + if (meline1 != nullptr) { meline1->display(I); } - if (meline2 != NULL) { + if (meline2 != nullptr) { meline2->display(I); } } void vpMbtDistanceCylinder::displayMovingEdges(const vpImage &I) { - if (meline1 != NULL) { + if (meline1 != nullptr) { meline1->display(I); } - if (meline2 != NULL) { + if (meline2 != nullptr) { meline2->display(I); } } diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp index 92651b06e4..7fdcba420c 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp @@ -55,9 +55,9 @@ void buildLine(vpPoint &P1, vpPoint &P2, vpPoint &P3, vpPoint &P4, vpLine &L); Basic constructor */ vpMbtDistanceLine::vpMbtDistanceLine() - : name(), index(0), cam(), me(NULL), isTrackedLine(true), isTrackedLineWithVisibility(true), wmean(1), featureline(), - poly(), useScanLine(false), meline(), line(NULL), p1(NULL), p2(NULL), L(), error(), nbFeature(), nbFeatureTotal(0), - Reinit(false), hiddenface(NULL), Lindex_polygon(), Lindex_polygon_tracked(), isvisible(false) + : name(), index(0), cam(), me(nullptr), isTrackedLine(true), isTrackedLineWithVisibility(true), wmean(1), featureline(), + poly(), useScanLine(false), meline(), line(nullptr), p1(nullptr), p2(nullptr), L(), error(), nbFeature(), nbFeatureTotal(0), + Reinit(false), hiddenface(nullptr), Lindex_polygon(), Lindex_polygon_tracked(), isvisible(false) { } /*! @@ -65,11 +65,11 @@ vpMbtDistanceLine::vpMbtDistanceLine() */ vpMbtDistanceLine::~vpMbtDistanceLine() { - if (line != NULL) + if (line != nullptr) delete line; for (unsigned int i = 0; i < meline.size(); i++) - if (meline[i] != NULL) + if (meline[i] != nullptr) delete meline[i]; meline.clear(); @@ -162,7 +162,7 @@ void buildLine(vpPoint &P1, vpPoint &P2, vpPoint &P3, vpPoint &P4, vpLine &L) */ void vpMbtDistanceLine::buildFrom(vpPoint &_p1, vpPoint &_p2, vpUniRand &rand_gen) { - if (line == NULL) { + if (line == nullptr) { line = new vpLine; } @@ -281,7 +281,7 @@ void vpMbtDistanceLine::setMovingEdge(vpMe *_me) me = _me; for (unsigned int i = 0; i < meline.size(); i++) - if (meline[i] != NULL) { + if (meline[i] != nullptr) { // nbFeature[i] = 0; meline[i]->reset(); meline[i]->setMe(me); @@ -298,14 +298,14 @@ void vpMbtDistanceLine::setMovingEdge(vpMe *_me) \param I : The image. \param cMo : The pose of the camera used to initialize the moving edges. \param doNotTrack : If true, ME are not tracked. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. \return false if an error occur, true otherwise. */ bool vpMbtDistanceLine::initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, bool doNotTrack, const vpImage *mask) { for (unsigned int i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) + if (meline[i] != nullptr) delete meline[i]; } @@ -434,7 +434,7 @@ void vpMbtDistanceLine::trackMovingEdge(const vpImage &I) } catch (...) { for (size_t i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) + if (meline[i] != nullptr) delete meline[i]; } @@ -477,7 +477,7 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const if (linesLst.size() != meline.size() || linesLst.size() == 0) { for (size_t i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) + if (meline[i] != nullptr) delete meline[i]; } @@ -494,7 +494,7 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const } catch (...) { for (size_t j = 0; j < meline.size(); j++) { - if (meline[j] != NULL) + if (meline[j] != nullptr) delete meline[j]; } @@ -556,7 +556,7 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const } catch (...) { for (size_t j = 0; j < meline.size(); j++) { - if (meline[j] != NULL) + if (meline[j] != nullptr) delete meline[j]; } @@ -570,7 +570,7 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const } else { for (size_t i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) + if (meline[i] != nullptr) delete meline[i]; } nbFeature.clear(); @@ -589,14 +589,14 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const \param I : the image. \param cMo : The pose of the camera. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. */ void vpMbtDistanceLine::reinitMovingEdge(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpImage *mask) { for (size_t i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) + if (meline[i] != nullptr) delete meline[i]; } @@ -677,7 +677,7 @@ void vpMbtDistanceLine::display(const vpImage &I, const vpHomogeneousMat void vpMbtDistanceLine::displayMovingEdges(const vpImage &I) { for (size_t i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) { + if (meline[i] != nullptr) { meline[i]->display(I); } } @@ -686,7 +686,7 @@ void vpMbtDistanceLine::displayMovingEdges(const vpImage &I) void vpMbtDistanceLine::displayMovingEdges(const vpImage &I) { for (size_t i = 0; i < meline.size(); i++) { - if (meline[i] != NULL) { + if (meline[i] != nullptr) { meline[i]->display(I); } } @@ -702,7 +702,7 @@ std::vector > vpMbtDistanceLine::getFeaturesForDisplay() for (size_t i = 0; i < meline.size(); i++) { vpMbtMeLine *me_l = meline[i]; - if (me_l != NULL) { + if (me_l != nullptr) { for (std::list::const_iterator it = me_l->getMeList().begin(); it != me_l->getMeList().end(); ++it) { vpMeSite p_me_l = *it; std::vector params = { 0, // ME diff --git a/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp b/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp index e7e81ad3f6..e670dc2744 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp @@ -183,7 +183,7 @@ void vpMbtMeEllipse::initTracking(const vpImage &I, const vpImage double n11_p, double n02_p, bool doNotTrack, vpImagePoint *pt1, const vpImagePoint *pt2) { - if (pt1 != NULL && pt2 != NULL) { + if (pt1 != nullptr && pt2 != nullptr) { m_trackArc = true; } @@ -238,7 +238,7 @@ void vpMbtMeEllipse::track(const vpImage &I) { try { vpMeTracker::track(I); - if (m_mask != NULL) { + if (m_mask != nullptr) { // Expected density could be modified if some vpMeSite are no more tracked because they are outside the mask. m_expectedDensity = static_cast(list.size()); } diff --git a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp index d0976d78dd..86940c13e8 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp @@ -561,7 +561,7 @@ void vpMbtMeLine::track(const vpImage &I) { try { vpMeTracker::track(I); - if (m_mask != NULL) { + if (m_mask != nullptr) { // Expected density could be modified if some vpMeSite are no more tracked because they are outside the mask. expecteddensity = (double)list.size(); } diff --git a/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp b/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp index 0aaf3e5250..911fc9692c 100644 --- a/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp +++ b/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp @@ -690,9 +690,9 @@ void vpMbEdgeKltTracker::computeVVS(const vpImage &I, const unsig if (nbInfos < 4) factorMBT = 1.; - if (edge_residual != NULL) + if (edge_residual != nullptr) *edge_residual = 0; - if (klt_residual != NULL) + if (klt_residual != nullptr) *klt_residual = 0; vpHomogeneousMatrix cMoPrev; @@ -788,7 +788,7 @@ void vpMbEdgeKltTracker::computeVVS(const vpImage &I, const unsig if (!reStartFromLastIncrement) { /* robust */ if (nbrow > 3) { - if (edge_residual != NULL) { + if (edge_residual != nullptr) { *edge_residual = 0; for (unsigned int i = 0; i < R_mbt.getRows(); i++) *edge_residual += fabs(R_mbt[i]); @@ -802,7 +802,7 @@ void vpMbEdgeKltTracker::computeVVS(const vpImage &I, const unsig } if (nbInfos > 3) { - if (klt_residual != NULL) { + if (klt_residual != nullptr) { *klt_residual = 0; for (unsigned int i = 0; i < R_klt.getRows(); i++) *klt_residual += fabs(R_klt[i]); @@ -1039,7 +1039,7 @@ unsigned int vpMbEdgeKltTracker::trackFirstLoop(const vpImage &I, for (size_t a = 0; a < l->meline.size(); a++) { std::list::const_iterator itListLine; - if (l->meline[a] != NULL) { + if (l->meline[a] != nullptr) { itListLine = l->meline[a]->getMeList().begin(); for (unsigned int i = 0; i < l->nbFeature[a]; i++) { @@ -1064,7 +1064,7 @@ unsigned int vpMbEdgeKltTracker::trackFirstLoop(const vpImage &I, std::list::const_iterator itCyl1; std::list::const_iterator itCyl2; - if ((cy->meline1 != NULL || cy->meline2 != NULL)) { + if ((cy->meline1 != nullptr || cy->meline2 != nullptr)) { itCyl1 = cy->meline1->getMeList().begin(); itCyl2 = cy->meline2->getMeList().begin(); } @@ -1095,7 +1095,7 @@ unsigned int vpMbEdgeKltTracker::trackFirstLoop(const vpImage &I, double fac = 1.0; std::list::const_iterator itCir; - if (ci->meEllipse != NULL) { + if (ci->meEllipse != nullptr) { itCir = ci->meEllipse->getMeList().begin(); } @@ -1404,20 +1404,20 @@ void vpMbEdgeKltTracker::reInitModel(const vpImage &I, const std: // delete the Klt Polygon features for (std::list::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it) { vpMbtDistanceKltPoints *kltpoly = *it; - if (kltpoly != NULL) { + if (kltpoly != nullptr) { delete kltpoly; } - kltpoly = NULL; + kltpoly = nullptr; } kltPolygons.clear(); for (std::list::const_iterator it = kltCylinders.begin(); it != kltCylinders.end(); ++it) { vpMbtDistanceKltCylinder *kltPolyCylinder = *it; - if (kltPolyCylinder != NULL) { + if (kltPolyCylinder != nullptr) { delete kltPolyCylinder; } - kltPolyCylinder = NULL; + kltPolyCylinder = nullptr; } kltCylinders.clear(); @@ -1425,10 +1425,10 @@ void vpMbEdgeKltTracker::reInitModel(const vpImage &I, const std: vpMbtDistanceCircle *ci; for (std::list::const_iterator it = circles_disp.begin(); it != circles_disp.end(); ++it) { ci = *it; - if (ci != NULL) { + if (ci != nullptr) { delete ci; } - ci = NULL; + ci = nullptr; } circles_disp.clear(); @@ -1443,24 +1443,24 @@ void vpMbEdgeKltTracker::reInitModel(const vpImage &I, const std: if (scales[i]) { for (std::list::const_iterator it = lines[i].begin(); it != lines[i].end(); ++it) { l = *it; - if (l != NULL) + if (l != nullptr) delete l; - l = NULL; + l = nullptr; } for (std::list::const_iterator it = cylinders[i].begin(); it != cylinders[i].end(); ++it) { cy = *it; - if (cy != NULL) + if (cy != nullptr) delete cy; - cy = NULL; + cy = nullptr; } for (std::list::const_iterator it = circles[i].begin(); it != circles[i].end(); ++it) { ci = *it; - if (ci != NULL) + if (ci != nullptr) delete ci; - ci = NULL; + ci = nullptr; } lines[i].clear(); diff --git a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp index 05f0bbce43..944a4c1ee8 100644 --- a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp +++ b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp @@ -138,30 +138,30 @@ vpMbKltTracker::~vpMbKltTracker() // delete the Klt Polygon features for (std::list::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it) { vpMbtDistanceKltPoints *kltpoly = *it; - if (kltpoly != NULL) { + if (kltpoly != nullptr) { delete kltpoly; } - kltpoly = NULL; + kltpoly = nullptr; } kltPolygons.clear(); for (std::list::const_iterator it = kltCylinders.begin(); it != kltCylinders.end(); ++it) { vpMbtDistanceKltCylinder *kltPolyCylinder = *it; - if (kltPolyCylinder != NULL) { + if (kltPolyCylinder != nullptr) { delete kltPolyCylinder; } - kltPolyCylinder = NULL; + kltPolyCylinder = nullptr; } kltCylinders.clear(); // delete the structures used to display circles for (std::list::const_iterator it = circles_disp.begin(); it != circles_disp.end(); ++it) { vpMbtDistanceCircle *ci = *it; - if (ci != NULL) { + if (ci != nullptr) { delete ci; } - ci = NULL; + ci = nullptr; } circles_disp.clear(); @@ -281,30 +281,30 @@ void vpMbKltTracker::resetTracker() // delete the Klt Polygon features for (std::list::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it) { vpMbtDistanceKltPoints *kltpoly = *it; - if (kltpoly != NULL) { + if (kltpoly != nullptr) { delete kltpoly; } - kltpoly = NULL; + kltpoly = nullptr; } kltPolygons.clear(); for (std::list::const_iterator it = kltCylinders.begin(); it != kltCylinders.end(); ++it) { vpMbtDistanceKltCylinder *kltPolyCylinder = *it; - if (kltPolyCylinder != NULL) { + if (kltPolyCylinder != nullptr) { delete kltPolyCylinder; } - kltPolyCylinder = NULL; + kltPolyCylinder = nullptr; } kltCylinders.clear(); // delete the structures used to display circles for (std::list::const_iterator it = circles_disp.begin(); it != circles_disp.end(); ++it) { vpMbtDistanceCircle *ci = *it; - if (ci != NULL) { + if (ci != nullptr) { delete ci; } - ci = NULL; + ci = nullptr; } circles_disp.clear(); @@ -606,7 +606,7 @@ void vpMbKltTracker::setPose(const vpImage *const I, const vpImag */ void vpMbKltTracker::setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) { - vpMbKltTracker::setPose(&I, NULL, cdMo); + vpMbKltTracker::setPose(&I, nullptr, cdMo); } /*! @@ -620,7 +620,7 @@ void vpMbKltTracker::setPose(const vpImage &I, const vpHomogeneou */ void vpMbKltTracker::setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) { - vpMbKltTracker::setPose(NULL, &I_color, cdMo); + vpMbKltTracker::setPose(nullptr, &I_color, cdMo); } /*! @@ -1391,30 +1391,30 @@ void vpMbKltTracker::reInitModel(const vpImage &I, const std::str // delete the Klt Polygon features for (std::list::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it) { vpMbtDistanceKltPoints *kltpoly = *it; - if (kltpoly != NULL) { + if (kltpoly != nullptr) { delete kltpoly; } - kltpoly = NULL; + kltpoly = nullptr; } kltPolygons.clear(); for (std::list::const_iterator it = kltCylinders.begin(); it != kltCylinders.end(); ++it) { vpMbtDistanceKltCylinder *kltPolyCylinder = *it; - if (kltPolyCylinder != NULL) { + if (kltPolyCylinder != nullptr) { delete kltPolyCylinder; } - kltPolyCylinder = NULL; + kltPolyCylinder = nullptr; } kltCylinders.clear(); // delete the structures used to display circles for (std::list::const_iterator it = circles_disp.begin(); it != circles_disp.end(); ++it) { vpMbtDistanceCircle *ci = *it; - if (ci != NULL) { + if (ci != nullptr) { delete ci; } - ci = NULL; + ci = nullptr; } faces.reset(); diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp index 68ae531fc1..a90ba01884 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp @@ -54,7 +54,7 @@ vpMbtDistanceKltCylinder::vpMbtDistanceKltCylinder() : c0Mo(), p1Ext(), p2Ext(), cylinder(), circle1(), circle2(), initPoints(), initPoints3D(), curPoints(), curPointsInd(), nbPointsCur(0), nbPointsInit(0), minNbPoint(4), enoughPoints(false), cam(), - isTrackedKltCylinder(true), listIndicesCylinderBBox(), hiddenface(NULL), useScanLine(false) + isTrackedKltCylinder(true), listIndicesCylinderBBox(), hiddenface(nullptr), useScanLine(false) { } /*! diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp index 9c67083b1a..2671cffd87 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp @@ -54,8 +54,8 @@ vpMbtDistanceKltPoints::vpMbtDistanceKltPoints() : H(), N(), N_cur(), invd0(1.), cRc0_0n(), initPoints(std::map()), curPoints(std::map()), curPointsInd(std::map()), nbPointsCur(0), nbPointsInit(0), - minNbPoint(4), enoughPoints(false), dt(1.), d0(1.), cam(), isTrackedKltPoints(true), polygon(NULL), - hiddenface(NULL), useScanLine(false) + minNbPoint(4), enoughPoints(false), dt(1.), d0(1.), cam(), isTrackedKltPoints(true), polygon(nullptr), + hiddenface(nullptr), useScanLine(false) { } /*! @@ -70,7 +70,7 @@ vpMbtDistanceKltPoints::~vpMbtDistanceKltPoints() { } points that are indeed in the face. \param _tracker : ViSP OpenCV KLT Tracker. - \param mask: Mask image or NULL if not wanted. Mask values that are set to true are considered in the tracking. To + \param mask: Mask image or nullptr if not wanted. Mask values that are set to true are considered in the tracking. To disable a pixel, set false. */ void vpMbtDistanceKltPoints::init(const vpKltOpencv &_tracker, const vpImage *mask) @@ -144,7 +144,7 @@ void vpMbtDistanceKltPoints::init(const vpKltOpencv &_tracker, const vpImage *mask) diff --git a/modules/tracker/mbt/src/vpMbGenericTracker.cpp b/modules/tracker/mbt/src/vpMbGenericTracker.cpp index d4b851ccef..830ff1577b 100644 --- a/modules/tracker/mbt/src/vpMbGenericTracker.cpp +++ b/modules/tracker/mbt/src/vpMbGenericTracker.cpp @@ -183,7 +183,7 @@ vpMbGenericTracker::~vpMbGenericTracker() for (std::map::iterator it = m_mapOfTrackers.begin(); it != m_mapOfTrackers.end(); ++it) { delete it->second; - it->second = NULL; + it->second = nullptr; } } @@ -1655,7 +1655,7 @@ void vpMbGenericTracker::getNbPolygon(std::map &mapOf polygon. \param index : Index of the polygon to return. - \return Pointer to the polygon index for the reference camera or NULL in + \return Pointer to the polygon index for the reference camera or nullptr in case of problem. */ vpMbtPolygon *vpMbGenericTracker::getPolygon(unsigned int index) @@ -1666,7 +1666,7 @@ vpMbtPolygon *vpMbGenericTracker::getPolygon(unsigned int index) } std::cerr << "The reference camera: " << m_referenceCameraName << " does not exist!" << std::endl; - return NULL; + return nullptr; } /*! @@ -1677,7 +1677,7 @@ vpMbtPolygon *vpMbGenericTracker::getPolygon(unsigned int index) \param cameraName : Name of the camera to return the polygon. \param index : Index of the polygon to return. - \return Pointer to the polygon index for the specified camera or NULL in + \return Pointer to the polygon index for the specified camera or nullptr in case of problem. */ vpMbtPolygon *vpMbGenericTracker::getPolygon(const std::string &cameraName, unsigned int index) @@ -1688,7 +1688,7 @@ vpMbtPolygon *vpMbGenericTracker::getPolygon(const std::string &cameraName, unsi } std::cerr << "The camera: " << cameraName << " does not exist!" << std::endl; - return NULL; + return nullptr; } /*! @@ -5449,13 +5449,13 @@ void vpMbGenericTracker::track(std::mapfirst] == NULL) { - throw vpException(vpException::fatalError, "Image pointer is NULL!"); + mapOfImages[it->first] == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); } if (tracker->m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && !mapOfPointClouds[it->first]) { // mapOfPointClouds[it->first] == nullptr - throw vpException(vpException::fatalError, "Pointcloud smart pointer is NULL!"); + throw vpException(vpException::fatalError, "Pointcloud smart pointer is nullptr!"); } } @@ -5526,22 +5526,22 @@ void vpMbGenericTracker::track(std::map *> &m | KLT_TRACKER #endif ) && - mapOfImages[it->first] == NULL) { - throw vpException(vpException::fatalError, "Image pointer is NULL!"); + mapOfImages[it->first] == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); } else if (tracker->m_trackerType & (EDGE_TRACKER #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) | KLT_TRACKER #endif ) && - mapOfImages[it->first] != NULL) { + mapOfImages[it->first] != nullptr) { vpImageConvert::convert(*mapOfColorImages[it->first], tracker->m_I); mapOfImages[it->first] = &tracker->m_I; // update grayscale image buffer } if (tracker->m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && !mapOfPointClouds[it->first]) { // mapOfPointClouds[it->first] == nullptr - throw vpException(vpException::fatalError, "Pointcloud smart pointer is NULL!"); + throw vpException(vpException::fatalError, "Pointcloud smart pointer is nullptr!"); } } @@ -5616,13 +5616,13 @@ void vpMbGenericTracker::track(std::mapfirst] == NULL) { - throw vpException(vpException::fatalError, "Image pointer is NULL!"); + mapOfImages[it->first] == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); } if (tracker->m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && - (mapOfPointClouds[it->first] == NULL)) { - throw vpException(vpException::fatalError, "Pointcloud is NULL!"); + (mapOfPointClouds[it->first] == nullptr)) { + throw vpException(vpException::fatalError, "Pointcloud is nullptr!"); } } @@ -5697,22 +5697,22 @@ void vpMbGenericTracker::track(std::map *> &m | KLT_TRACKER #endif ) && - mapOfColorImages[it->first] == NULL) { - throw vpException(vpException::fatalError, "Image pointer is NULL!"); + mapOfColorImages[it->first] == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); } else if (tracker->m_trackerType & (EDGE_TRACKER #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) | KLT_TRACKER #endif ) && - mapOfColorImages[it->first] != NULL) { + mapOfColorImages[it->first] != nullptr) { vpImageConvert::convert(*mapOfColorImages[it->first], tracker->m_I); mapOfImages[it->first] = &tracker->m_I; // update grayscale image buffer } if (tracker->m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && - (mapOfPointClouds[it->first] == NULL)) { - throw vpException(vpException::fatalError, "Pointcloud is NULL!"); + (mapOfPointClouds[it->first] == nullptr)) { + throw vpException(vpException::fatalError, "Pointcloud is nullptr!"); } } @@ -6847,24 +6847,24 @@ void vpMbGenericTracker::TrackerWrapper::reInitModel(const vpImage::const_iterator it = lines[i].begin(); it != lines[i].end(); ++it) { l = *it; - if (l != NULL) + if (l != nullptr) delete l; - l = NULL; + l = nullptr; } for (std::list::const_iterator it = cylinders[i].begin(); it != cylinders[i].end(); ++it) { cy = *it; - if (cy != NULL) + if (cy != nullptr) delete cy; - cy = NULL; + cy = nullptr; } for (std::list::const_iterator it = circles[i].begin(); it != circles[i].end(); ++it) { ci = *it; - if (ci != NULL) + if (ci != nullptr) delete ci; - ci = NULL; + ci = nullptr; } lines[i].clear(); @@ -6883,30 +6883,30 @@ void vpMbGenericTracker::TrackerWrapper::reInitModel(const vpImage::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it) { vpMbtDistanceKltPoints *kltpoly = *it; - if (kltpoly != NULL) { + if (kltpoly != nullptr) { delete kltpoly; } - kltpoly = NULL; + kltpoly = nullptr; } kltPolygons.clear(); for (std::list::const_iterator it = kltCylinders.begin(); it != kltCylinders.end(); ++it) { vpMbtDistanceKltCylinder *kltPolyCylinder = *it; - if (kltPolyCylinder != NULL) { + if (kltPolyCylinder != nullptr) { delete kltPolyCylinder; } - kltPolyCylinder = NULL; + kltPolyCylinder = nullptr; } kltCylinders.clear(); // delete the structures used to display circles for (std::list::const_iterator it = circles_disp.begin(); it != circles_disp.end(); ++it) { ci = *it; - if (ci != NULL) { + if (ci != nullptr) { delete ci; } - ci = NULL; + ci = nullptr; } circles_disp.clear(); @@ -6917,14 +6917,14 @@ void vpMbGenericTracker::TrackerWrapper::reInitModel(const vpImage &I_color, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose, const vpHomogeneousMatrix &T) { - reInitModel(NULL, &I_color, cad_name, cMo, verbose, T); + reInitModel(nullptr, &I_color, cad_name, cMo, verbose, T); } void vpMbGenericTracker::TrackerWrapper::resetTracker() @@ -7061,12 +7061,12 @@ void vpMbGenericTracker::TrackerWrapper::setPose(const vpImage *c void vpMbGenericTracker::TrackerWrapper::setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) { - setPose(&I, NULL, cdMo); + setPose(&I, nullptr, cdMo); } void vpMbGenericTracker::TrackerWrapper::setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) { - setPose(NULL, &I_color, cdMo); + setPose(nullptr, &I_color, cdMo); } void vpMbGenericTracker::TrackerWrapper::setProjectionErrorComputation(const bool &flag) @@ -7147,12 +7147,12 @@ void vpMbGenericTracker::TrackerWrapper::track(const vpImage *con | KLT_TRACKER #endif ) && - ptr_I == NULL) { - throw vpException(vpException::fatalError, "Image pointer is NULL!"); + ptr_I == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); } if (m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && !point_cloud) { // point_cloud == nullptr - throw vpException(vpException::fatalError, "Pointcloud smart pointer is NULL!"); + throw vpException(vpException::fatalError, "Pointcloud smart pointer is nullptr!"); } // Back-up cMo in case of exception diff --git a/modules/tracker/mbt/src/vpMbScanLine.cpp b/modules/tracker/mbt/src/vpMbScanLine.cpp index eda449b580..3ace72ea3f 100644 --- a/modules/tracker/mbt/src/vpMbScanLine.cpp +++ b/modules/tracker/mbt/src/vpMbScanLine.cpp @@ -62,7 +62,7 @@ vpMbScanLine::vpMbScanLine() : w(0), h(0), K(), maskBorder(0), mask(), primitive_ids(), visibility_samples(), depthTreshold(1e-06) #if defined(DEBUG_DISP) , - dispMaskDebug(NULL), dispLineDebug(NULL), linedebugImg() + dispMaskDebug(nullptr), dispLineDebug(nullptr), linedebugImg() #endif { #if defined(VISP_HAVE_X11) && defined(DEBUG_DISP) @@ -77,9 +77,9 @@ vpMbScanLine::vpMbScanLine() vpMbScanLine::~vpMbScanLine() { #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(DEBUG_DISP) - if (dispLineDebug != NULL) + if (dispLineDebug != nullptr) delete dispLineDebug; - if (dispMaskDebug != NULL) + if (dispMaskDebug != nullptr) delete dispMaskDebug; #endif } diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index b4beb1e3a6..45a27cd8f4 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -188,7 +188,7 @@ vpMbTracker::vpMbTracker() m_projectionErrorLines(), m_projectionErrorCylinders(), m_projectionErrorCircles(), m_projectionErrorFaces(), m_projectionErrorOgreShowConfigDialog(false), m_projectionErrorMe(), m_projectionErrorKernelSize(2), m_SobelX(5, 5), m_SobelY(5, 5), m_projectionErrorDisplay(false), m_projectionErrorDisplayLength(20), - m_projectionErrorDisplayThickness(1), m_projectionErrorCam(), m_mask(NULL), m_I(), m_sodb_init_called(false), + m_projectionErrorDisplayThickness(1), m_projectionErrorCam(), m_mask(nullptr), m_I(), m_sodb_init_called(false), m_rand() { oJo.eye(); @@ -208,25 +208,25 @@ vpMbTracker::~vpMbTracker() for (std::vector::const_iterator it = m_projectionErrorLines.begin(); it != m_projectionErrorLines.end(); ++it) { vpMbtDistanceLine *l = *it; - if (l != NULL) + if (l != nullptr) delete l; - l = NULL; + l = nullptr; } for (std::vector::const_iterator it = m_projectionErrorCylinders.begin(); it != m_projectionErrorCylinders.end(); ++it) { vpMbtDistanceCylinder *cy = *it; - if (cy != NULL) + if (cy != nullptr) delete cy; - cy = NULL; + cy = nullptr; } for (std::vector::const_iterator it = m_projectionErrorCircles.begin(); it != m_projectionErrorCircles.end(); ++it) { vpMbtDistanceCircle *ci = *it; - if (ci != NULL) + if (ci != nullptr) delete ci; - ci = NULL; + ci = nullptr; } #if defined(VISP_HAVE_COIN3D) && (COIN_MAJOR_VERSION >= 2) if (m_sodb_init_called) { @@ -319,7 +319,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage m_cMo = last_cMo; } else { - vpDisplay *d_help = NULL; + vpDisplay *d_help = nullptr; if (I) { vpDisplay::display(*I); @@ -389,9 +389,9 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpImage Iref; vpImageIo::read(Iref, dispF); #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV) - const int winXPos = I != NULL ? I->display->getWindowXPosition() : I_color->display->getWindowXPosition(); - const int winYPos = I != NULL ? I->display->getWindowYPosition() : I_color->display->getWindowYPosition(); - unsigned int width = I != NULL ? I->getWidth() : I_color->getWidth(); + const int winXPos = I != nullptr ? I->display->getWindowXPosition() : I_color->display->getWindowXPosition(); + const int winYPos = I != nullptr ? I->display->getWindowYPosition() : I_color->display->getWindowYPosition(); + unsigned int width = I != nullptr ? I->getWidth() : I_color->getWidth(); d_help->init(Iref, winXPos + (int)width + 80, winYPos, "Where to initialize..."); vpDisplay::display(Iref); vpDisplay::flush(Iref); @@ -400,9 +400,9 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage } } catch (...) { - if (d_help != NULL) { + if (d_help != nullptr) { delete d_help; - d_help = NULL; + d_help = nullptr; } } #else //#ifdef VISP_HAVE_MODULE_IO @@ -545,9 +545,9 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage else savePose(poseSavingFilename); - if (d_help != NULL) { + if (d_help != nullptr) { delete d_help; - d_help = NULL; + d_help = nullptr; } } @@ -595,7 +595,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage void vpMbTracker::initClick(const vpImage &I, const std::string &initFile, bool displayHelp, const vpHomogeneousMatrix &T) { - initClick(&I, NULL, initFile, displayHelp, T); + initClick(&I, nullptr, initFile, displayHelp, T); } /*! @@ -632,7 +632,7 @@ void vpMbTracker::initClick(const vpImage &I, const std::string & void vpMbTracker::initClick(const vpImage &I_color, const std::string &initFile, bool displayHelp, const vpHomogeneousMatrix &T) { - initClick(NULL, &I_color, initFile, displayHelp, T); + initClick(nullptr, &I_color, initFile, displayHelp, T); } void vpMbTracker::initClick(const vpImage *const I, const vpImage *const I_color, @@ -647,7 +647,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpDisplay::flush(*I_color); } - vpDisplay *d_help = NULL; + vpDisplay *d_help = nullptr; vpPose pose; std::vector P; @@ -683,9 +683,9 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage #endif } catch (...) { - if (d_help != NULL) { + if (d_help != nullptr) { delete d_help; - d_help = NULL; + d_help = nullptr; } } } @@ -780,9 +780,9 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpDisplay::displayFrame(*I_color, m_cMo, m_cam, 0.05, vpColor::red); } - if (d_help != NULL) { + if (d_help != nullptr) { delete d_help; - d_help = NULL; + d_help = nullptr; } if (I) @@ -807,7 +807,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage void vpMbTracker::initClick(const vpImage &I, const std::vector &points3D_list, const std::string &displayFile) { - initClick(&I, NULL, points3D_list, displayFile); + initClick(&I, nullptr, points3D_list, displayFile); } /*! @@ -824,7 +824,7 @@ void vpMbTracker::initClick(const vpImage &I, const std::vector &I_color, const std::vector &points3D_list, const std::string &displayFile) { - initClick(NULL, &I_color, points3D_list, displayFile); + initClick(nullptr, &I_color, points3D_list, displayFile); } #endif //#ifdef VISP_HAVE_MODULE_GUI @@ -984,7 +984,7 @@ void vpMbTracker::initFromPoints(const vpImage *const I, const vp */ void vpMbTracker::initFromPoints(const vpImage &I, const std::string &initFile) { - initFromPoints(&I, NULL, initFile); + initFromPoints(&I, nullptr, initFile); } /*! @@ -1013,7 +1013,7 @@ void vpMbTracker::initFromPoints(const vpImage &I, const std::str */ void vpMbTracker::initFromPoints(const vpImage &I_color, const std::string &initFile) { - initFromPoints(NULL, &I_color, initFile); + initFromPoints(nullptr, &I_color, initFile); } void vpMbTracker::initFromPoints(const vpImage *const I, const vpImage *const I_color, @@ -1059,7 +1059,7 @@ void vpMbTracker::initFromPoints(const vpImage *const I, const vp void vpMbTracker::initFromPoints(const vpImage &I, const std::vector &points2D_list, const std::vector &points3D_list) { - initFromPoints(&I, NULL, points2D_list, points3D_list); + initFromPoints(&I, nullptr, points2D_list, points3D_list); } /*! @@ -1073,7 +1073,7 @@ void vpMbTracker::initFromPoints(const vpImage &I, const std::vec void vpMbTracker::initFromPoints(const vpImage &I_color, const std::vector &points2D_list, const std::vector &points3D_list) { - initFromPoints(NULL, &I_color, points2D_list, points3D_list); + initFromPoints(nullptr, &I_color, points2D_list, points3D_list); } void vpMbTracker::initFromPose(const vpImage *const I, const vpImage *const I_color, @@ -1135,7 +1135,7 @@ void vpMbTracker::initFromPose(const vpImage *const I, const vpIm */ void vpMbTracker::initFromPose(const vpImage &I, const std::string &initFile) { - initFromPose(&I, NULL, initFile); + initFromPose(&I, nullptr, initFile); } /*! @@ -1158,7 +1158,7 @@ void vpMbTracker::initFromPose(const vpImage &I, const std::strin */ void vpMbTracker::initFromPose(const vpImage &I_color, const std::string &initFile) { - initFromPose(NULL, &I_color, initFile); + initFromPose(nullptr, &I_color, initFile); } /*! @@ -1516,7 +1516,7 @@ void vpMbTracker::loadVRMLModel(const std::string &modelFile) if (!in.isFileVRML2()) { SoSeparator *sceneGraph = SoDB::readAll(&in); - if (sceneGraph == NULL) { /*return -1;*/ + if (sceneGraph == nullptr) { /*return -1;*/ } sceneGraph->ref(); @@ -1529,7 +1529,7 @@ void vpMbTracker::loadVRMLModel(const std::string &modelFile) } else { sceneGraphVRML2 = SoDB::readAllVRML(&in); - if (sceneGraphVRML2 == NULL) { /*return -1;*/ + if (sceneGraphVRML2 == nullptr) { /*return -1;*/ } sceneGraphVRML2->ref(); } @@ -1684,7 +1684,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector::max(), fileId.widen('\n')); // skip the rest of the line nbLines += caoNbrLine; - unsigned int *caoLinePoints = NULL; + unsigned int *caoLinePoints = nullptr; if (verbose || (parent && !header)) { std::lock_guard lock(g_mutex_cout); std::cout << "> " << caoNbrLine << " lines" << std::endl; @@ -2883,7 +2883,7 @@ void vpMbTracker::computeVVSCheckLevenbergMarquardt(unsigned int iter, vpColVect m_cMo = cMoPrev; error = m_error_prev; - if (w != NULL && m_w_prev != NULL) { + if (w != nullptr && m_w_prev != nullptr) { *w = *m_w_prev; } reStartFromLastIncrement = true; @@ -2911,7 +2911,7 @@ void vpMbTracker::computeVVSPoseEstimation(const bool isoJoIdentity, unsigned in mu /= 10.0; error_prev = error; - if (w != NULL && m_w_prev != NULL) + if (w != nullptr && m_w_prev != nullptr) *m_w_prev = *w; break; } @@ -2942,7 +2942,7 @@ void vpMbTracker::computeVVSPoseEstimation(const bool isoJoIdentity, unsigned in mu /= 10.0; error_prev = error; - if (w != NULL && m_w_prev != NULL) + if (w != nullptr && m_w_prev != nullptr) *m_w_prev = *w; break; } @@ -3536,7 +3536,7 @@ double vpMbTracker::computeProjectionErrorImpl(const vpImage &I, vpMbtDistanceLine *l = *it; if (l->isVisible() && l->isTracked()) { for (size_t a = 0; a < l->meline.size(); a++) { - if (l->meline[a] != NULL) { + if (l->meline[a] != nullptr) { double lineNormGradient; unsigned int lineNbFeatures; l->meline[a]->computeProjectionError(I, lineNormGradient, lineNbFeatures, m_SobelX, m_SobelY, @@ -3553,7 +3553,7 @@ double vpMbTracker::computeProjectionErrorImpl(const vpImage &I, it != m_projectionErrorCylinders.end(); ++it) { vpMbtDistanceCylinder *cy = *it; if (cy->isVisible() && cy->isTracked()) { - if (cy->meline1 != NULL) { + if (cy->meline1 != nullptr) { double cylinderNormGradient = 0; unsigned int cylinderNbFeatures = 0; cy->meline1->computeProjectionError(I, cylinderNormGradient, cylinderNbFeatures, m_SobelX, m_SobelY, @@ -3563,7 +3563,7 @@ double vpMbTracker::computeProjectionErrorImpl(const vpImage &I, nbFeatures += cylinderNbFeatures; } - if (cy->meline2 != NULL) { + if (cy->meline2 != nullptr) { double cylinderNormGradient = 0; unsigned int cylinderNbFeatures = 0; cy->meline2->computeProjectionError(I, cylinderNormGradient, cylinderNbFeatures, m_SobelX, m_SobelY, @@ -3578,7 +3578,7 @@ double vpMbTracker::computeProjectionErrorImpl(const vpImage &I, for (std::vector::const_iterator it = m_projectionErrorCircles.begin(); it != m_projectionErrorCircles.end(); ++it) { vpMbtDistanceCircle *c = *it; - if (c->isVisible() && c->isTracked() && c->meEllipse != NULL) { + if (c->isVisible() && c->isTracked() && c->meEllipse != nullptr) { double circleNormGradient = 0; unsigned int circleNbFeatures = 0; c->meEllipse->computeProjectionError(I, circleNormGradient, circleNbFeatures, m_SobelX, m_SobelY, @@ -3616,9 +3616,9 @@ void vpMbTracker::projectionErrorResetMovingEdges() for (std::vector::const_iterator it = m_projectionErrorLines.begin(); it != m_projectionErrorLines.end(); ++it) { for (size_t a = 0; a < (*it)->meline.size(); a++) { - if ((*it)->meline[a] != NULL) { + if ((*it)->meline[a] != nullptr) { delete (*it)->meline[a]; - (*it)->meline[a] = NULL; + (*it)->meline[a] = nullptr; } } @@ -3629,13 +3629,13 @@ void vpMbTracker::projectionErrorResetMovingEdges() for (std::vector::const_iterator it = m_projectionErrorCylinders.begin(); it != m_projectionErrorCylinders.end(); ++it) { - if ((*it)->meline1 != NULL) { + if ((*it)->meline1 != nullptr) { delete (*it)->meline1; - (*it)->meline1 = NULL; + (*it)->meline1 = nullptr; } - if ((*it)->meline2 != NULL) { + if ((*it)->meline2 != nullptr) { delete (*it)->meline2; - (*it)->meline2 = NULL; + (*it)->meline2 = nullptr; } (*it)->nbFeature = 0; @@ -3645,9 +3645,9 @@ void vpMbTracker::projectionErrorResetMovingEdges() for (std::vector::const_iterator it = m_projectionErrorCircles.begin(); it != m_projectionErrorCircles.end(); ++it) { - if ((*it)->meEllipse != NULL) { + if ((*it)->meEllipse != nullptr) { delete (*it)->meEllipse; - (*it)->meEllipse = NULL; + (*it)->meEllipse = nullptr; } (*it)->nbFeature = 0; } @@ -3686,7 +3686,7 @@ void vpMbTracker::projectionErrorInitMovingEdge(const vpImage &I, else { l->setVisible(false); for (size_t a = 0; a < l->meline.size(); a++) { - if (l->meline[a] != NULL) + if (l->meline[a] != nullptr) delete l->meline[a]; if (a < l->nbFeature.size()) l->nbFeature[a] = 0; @@ -3714,19 +3714,19 @@ void vpMbTracker::projectionErrorInitMovingEdge(const vpImage &I, if (isvisible) { cy->setVisible(true); - if (cy->meline1 == NULL || cy->meline2 == NULL) { + if (cy->meline1 == nullptr || cy->meline2 == nullptr) { if (cy->isTracked()) cy->initMovingEdge(I, _cMo, doNotTrack, m_mask); } } else { cy->setVisible(false); - if (cy->meline1 != NULL) + if (cy->meline1 != nullptr) delete cy->meline1; - if (cy->meline2 != NULL) + if (cy->meline2 != nullptr) delete cy->meline2; - cy->meline1 = NULL; - cy->meline2 = NULL; + cy->meline1 = nullptr; + cy->meline2 = nullptr; cy->nbFeature = 0; cy->nbFeaturel1 = 0; cy->nbFeaturel2 = 0; @@ -3748,16 +3748,16 @@ void vpMbTracker::projectionErrorInitMovingEdge(const vpImage &I, if (isvisible) { ci->setVisible(true); - if (ci->meEllipse == NULL) { + if (ci->meEllipse == nullptr) { if (ci->isTracked()) ci->initMovingEdge(I, _cMo, doNotTrack, m_mask); } } else { ci->setVisible(false); - if (ci->meEllipse != NULL) + if (ci->meEllipse != nullptr) delete ci->meEllipse; - ci->meEllipse = NULL; + ci->meEllipse = nullptr; ci->nbFeature = 0; } } diff --git a/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp b/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp index bfdc7900e5..c3707d7735 100644 --- a/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp +++ b/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp @@ -79,7 +79,7 @@ class vpMbtXmlGenericParser::Impl // https://en.cppreference.com/w/cpp/locale/setlocale // When called from Java binding, the locale seems to be changed to the default system locale // It thus mess with the parsing of numbers with pugixml and comma decimal separator environment - if (std::setlocale(LC_ALL, "C") == NULL) { + if (std::setlocale(LC_ALL, "C") == nullptr) { std::cerr << "Cannot set locale to C" << std::endl; } m_call_setlocale = false; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index 2167f43c26..03273fbce1 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -159,7 +159,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all use_color_image = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -172,7 +172,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -706,7 +706,7 @@ int main(int argc, const char *argv[]) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp index bcdbe470f0..23af518084 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp @@ -137,7 +137,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all use_color_image = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -150,7 +150,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -469,7 +469,7 @@ int main(int argc, const char *argv[]) // Test if an input path is set if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl << " environment variable to specify the location of the " << std::endl diff --git a/modules/tracker/mbt/test/testTukeyEstimator.cpp b/modules/tracker/mbt/test/testTukeyEstimator.cpp index 95810fe5fd..6b9aa248fa 100644 --- a/modules/tracker/mbt/test/testTukeyEstimator.cpp +++ b/modules/tracker/mbt/test/testTukeyEstimator.cpp @@ -54,7 +54,7 @@ int main() double stdev = 0.5, mean = 0.0, noise_threshold = 1e-3; vpGaussRand noise(stdev, mean); - noise.seed((unsigned int)time(NULL)); + noise.seed((unsigned int)time(nullptr)); vpColVector residues_col((unsigned int)nb_elements); vpColVector weights_col, weights_col_save; diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index e71ffad56b..41b24437dc 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -257,12 +257,12 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * \param I : Image in which the ellipse appears. * \param param : Vector with the five parameters \f$(u_c, v_c, n_{20}, n_{11}, n_{02})\f$ defining the ellipse * (expressed in pixels). - * \param pt1 : Image point defining the first extremity of the arc or NULL to track a complete ellipse. - * \param pt2 : Image point defining the second extremity of the arc or NULL to track a complete ellipse. + * \param pt1 : Image point defining the first extremity of the arc or nullptr to track a complete ellipse. + * \param pt2 : Image point defining the second extremity of the arc or nullptr to track a complete ellipse. * \param trackCircle : When true enable tracking of a circle, when false the tracking of an ellipse. */ - void initTracking(const vpImage &I, const vpColVector ¶m, vpImagePoint *pt1 = NULL, - const vpImagePoint *pt2 = NULL, bool trackCircle = false); + void initTracking(const vpImage &I, const vpColVector ¶m, vpImagePoint *pt1 = nullptr, + const vpImagePoint *pt2 = nullptr, bool trackCircle = false); /*! * Print the parameters \f$ K = {K_0, ..., K_5} \f$, the coordinates of the diff --git a/modules/tracker/me/include/visp3/me/vpMeTracker.h b/modules/tracker/me/include/visp3/me/vpMeTracker.h index 743799af19..758d3cbbaf 100644 --- a/modules/tracker/me/include/visp3/me/vpMeTracker.h +++ b/modules/tracker/me/include/visp3/me/vpMeTracker.h @@ -146,7 +146,7 @@ class VISP_EXPORT vpMeTracker : public vpTracker * Test whether the pixel is inside the mask. Mask values that are set to true * are considered in the tracking. * - * \param mask: Mask image or NULL if not wanted. Mask values that are set to true + * \param mask: Mask image or nullptr if not wanted. Mask values that are set to true * are considered in the tracking. To disable a pixel, set false. * \param i : Pixel coordinate along the rows. * \param j : Pixel coordinate along the columns. diff --git a/modules/tracker/me/src/moving-edges/vpMe.cpp b/modules/tracker/me/src/moving-edges/vpMe.cpp index f58df242ab..1ad911484c 100644 --- a/modules/tracker/me/src/moving-edges/vpMe.cpp +++ b/modules/tracker/me/src/moving-edges/vpMe.cpp @@ -328,7 +328,7 @@ static void calcul_masques(vpColVector &angle, // definitions des angles theta void vpMe::initMask() { - if (m_mask != NULL) + if (m_mask != nullptr) delete[] m_mask; m_mask = new vpMatrix[m_mask_number]; @@ -364,7 +364,7 @@ void vpMe::print() vpMe::vpMe() : m_likelihood_threshold_type(OLD_THRESHOLD), m_threshold(10000), m_mu1(0.5), m_mu2(0.5), m_min_samplestep(4), m_anglestep(1), m_mask_sign(0), m_range(4), m_sample_step(10), - m_ntotal_sample(0), m_points_to_track(500), m_mask_size(5), m_mask_number(180), m_strip(2), m_mask(NULL) + m_ntotal_sample(0), m_points_to_track(500), m_mask_size(5), m_mask_number(180), m_strip(2), m_mask(nullptr) { m_anglestep = (180 / m_mask_number); @@ -374,16 +374,16 @@ vpMe::vpMe() vpMe::vpMe(const vpMe &me) : m_likelihood_threshold_type(OLD_THRESHOLD), m_threshold(10000), m_mu1(0.5), m_mu2(0.5), m_min_samplestep(4), m_anglestep(1), m_mask_sign(0), m_range(4), m_sample_step(10), - m_ntotal_sample(0), m_points_to_track(500), m_mask_size(5), m_mask_number(180), m_strip(2), m_mask(NULL) + m_ntotal_sample(0), m_points_to_track(500), m_mask_size(5), m_mask_number(180), m_strip(2), m_mask(nullptr) { *this = me; } vpMe &vpMe::operator=(const vpMe &me) { - if (m_mask != NULL) { + if (m_mask != nullptr) { delete[] m_mask; - m_mask = NULL; + m_mask = nullptr; } m_likelihood_threshold_type = me.m_likelihood_threshold_type; @@ -407,9 +407,9 @@ vpMe &vpMe::operator=(const vpMe &me) vpMe &vpMe::operator=(const vpMe &&me) { - if (m_mask != NULL) { + if (m_mask != nullptr) { delete[] m_mask; - m_mask = NULL; + m_mask = nullptr; } m_likelihood_threshold_type = std::move(me.m_likelihood_threshold_type); m_threshold = std::move(me.m_threshold); @@ -432,9 +432,9 @@ vpMe &vpMe::operator=(const vpMe &&me) vpMe::~vpMe() { - if (m_mask != NULL) { + if (m_mask != nullptr) { delete[] m_mask; - m_mask = NULL; + m_mask = nullptr; } } diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index e21a6badac..cfc355620b 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -1081,7 +1081,7 @@ void vpMeEllipse::initTracking(const vpImage &I, const vpColVecto const vpImagePoint *pt2, bool trackCircle) { m_trackCircle = trackCircle; - if (pt1 != NULL && pt2 != NULL) { + if (pt1 != nullptr && pt2 != nullptr) { m_trackArc = true; } // useful for sample(I) : uc, vc, a, b, e, Ki, alpha1, alpha2 diff --git a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp index d6c28a541b..4d932953d7 100644 --- a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp @@ -241,10 +241,10 @@ void vpMeNurbs::sample(const vpImage &I, bool doNotTrack) list.clear(); double u = 0.0; - vpImagePoint *pt = NULL; + vpImagePoint *pt = nullptr; vpImagePoint pt_1(-rows, -cols); while (u <= 1.0) { - if (pt != NULL) + if (pt != nullptr) delete[] pt; pt = nurbs.computeCurveDersPoint(u, 1); double delta = computeDelta(pt[1].get_i(), pt[1].get_j()); @@ -261,7 +261,7 @@ void vpMeNurbs::sample(const vpImage &I, bool doNotTrack) } u = u + step; } - if (pt != NULL) + if (pt != nullptr) delete[] pt; } @@ -286,7 +286,7 @@ void vpMeNurbs::updateDelta() std::list::iterator it = list.begin(); vpImagePoint Cu; - vpImagePoint *der = NULL; + vpImagePoint *der = nullptr; double step = 0.01; while (u < 1 && it != list.end()) { vpMeSite s = *it; @@ -299,7 +299,7 @@ void vpMeNurbs::updateDelta() } u -= step; - if (der != NULL) + if (der != nullptr) delete[] der; der = nurbs.computeCurveDersPoint(u, 1); // vpImagePoint toto(der[0].get_i(),der[0].get_j()); @@ -311,7 +311,7 @@ void vpMeNurbs::updateDelta() d = 1e6; d_1 = 1.5e6; } - if (der != NULL) + if (der != nullptr) delete[] der; } @@ -320,8 +320,8 @@ void vpMeNurbs::seekExtremities(const vpImage &I) int rows = (int)I.getHeight(); int cols = (int)I.getWidth(); - vpImagePoint *begin = NULL; - vpImagePoint *end = NULL; + vpImagePoint *begin = nullptr; + vpImagePoint *end = nullptr; begin = nurbs.computeCurveDersPoint(0.0, 1); end = nurbs.computeCurveDersPoint(1.0, 1); @@ -421,8 +421,8 @@ void vpMeNurbs::seekExtremities(const vpImage &I) else { list.pop_front(); } - /*if(begin != NULL)*/ delete[] begin; - /*if(end != NULL) */ delete[] end; + /*if(begin != nullptr)*/ delete[] begin; + /*if(end != nullptr) */ delete[] end; } void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) @@ -432,7 +432,7 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) pt = list.back(); vpImagePoint lastPoint(pt.ifloat, pt.jfloat); if (beginPtFound >= 3 && farFromImageEdge(I, firstPoint)) { - vpImagePoint *begin = NULL; + vpImagePoint *begin = nullptr; begin = nurbs.computeCurveDersPoint(0.0, 1); vpImage Isub(32, 32); // Sub image. vpImagePoint topLeft(begin[0].get_i() - 15, begin[0].get_j() - 15); @@ -552,12 +552,12 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) me->setRange(memory_range); } - /* if (begin != NULL) */ delete[] begin; + /* if (begin != nullptr) */ delete[] begin; beginPtFound = 0; } if (endPtFound >= 3 && farFromImageEdge(I, lastPoint)) { - vpImagePoint *end = NULL; + vpImagePoint *end = nullptr; end = nurbs.computeCurveDersPoint(1.0, 1); vpImage Isub(32, 32); // Sub image. @@ -682,7 +682,7 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) me->setRange(memory_range); } - /* if (end != NULL) */ delete[] end; + /* if (end != nullptr) */ delete[] end; endPtFound = 0; } } @@ -702,7 +702,7 @@ void vpMeNurbs::localReSample(const vpImage &I) { int rows = (int)I.getHeight(); int cols = (int)I.getWidth(); - vpImagePoint *iP = NULL; + vpImagePoint *iP = nullptr; int n = (int)numberOfSignal(); @@ -753,9 +753,9 @@ void vpMeNurbs::localReSample(const vpImage &I) while (vpImagePoint::sqrDistance(iP[0], iPend) > vpMath::sqr(me->getSampleStep()) && u < uend) { u += 0.01; - /*if (iP!=NULL)*/ { + /*if (iP!=nullptr)*/ { delete[] iP; - iP = NULL; + iP = nullptr; } iP = nurbs.computeCurveDersPoint(u, 1); if (vpImagePoint::sqrDistance(iP[0], iP_1) > vpMath::sqr(me->getSampleStep()) && @@ -771,9 +771,9 @@ void vpMeNurbs::localReSample(const vpImage &I) } } } - /*if (iP!=NULL)*/ { + /*if (iP!=nullptr)*/ { delete[] iP; - iP = NULL; + iP = nullptr; } } } diff --git a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp index 7ff2234fe0..111a5f2e02 100644 --- a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp @@ -55,7 +55,7 @@ void vpMeTracker::init() } vpMeTracker::vpMeTracker() - : list(), me(NULL), init_range(1), nGoodElement(0), m_mask(NULL), selectDisplay(vpMeSite::NONE) + : list(), me(nullptr), init_range(1), nGoodElement(0), m_mask(nullptr), selectDisplay(vpMeSite::NONE) #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS , query_range(0), display_point(false) @@ -65,7 +65,7 @@ vpMeTracker::vpMeTracker() } vpMeTracker::vpMeTracker(const vpMeTracker &meTracker) - : vpTracker(meTracker), list(), me(NULL), init_range(1), nGoodElement(0), m_mask(NULL), selectDisplay(vpMeSite::NONE) + : vpTracker(meTracker), list(), me(nullptr), init_range(1), nGoodElement(0), m_mask(nullptr), selectDisplay(vpMeSite::NONE) #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS , query_range(0), display_point(false) @@ -123,7 +123,7 @@ unsigned int vpMeTracker::totalNumberOfSignal() { return (unsigned int)list.size bool vpMeTracker::inMask(const vpImage *mask, unsigned int i, unsigned int j) { try { - return (mask == NULL || mask->getValue(i, j)); + return (mask == nullptr || mask->getValue(i, j)); } catch (vpException &) { return false; diff --git a/modules/tracker/me/src/moving-edges/vpNurbs.cpp b/modules/tracker/me/src/moving-edges/vpNurbs.cpp index c253f55ea7..5a8dd1a08f 100644 --- a/modules/tracker/me/src/moving-edges/vpNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpNurbs.cpp @@ -53,7 +53,7 @@ vpNurbs::vpNurbs(const vpNurbs &nurbs) : vpBSpline(nurbs), weights(nurbs.weights vpImagePoint vpNurbs::computeCurvePoint(double l_u, unsigned int l_i, unsigned int l_p, std::vector &l_knots, std::vector &l_controlPoints, std::vector &l_weights) { - vpBasisFunction *N = NULL; + vpBasisFunction *N = nullptr; N = computeBasisFuns(l_u, l_i, l_p, l_knots); vpImagePoint pt; @@ -69,7 +69,7 @@ vpImagePoint vpNurbs::computeCurvePoint(double l_u, unsigned int l_i, unsigned i pt.set_i(ic / wc); pt.set_j(jc / wc); - if (N != NULL) + if (N != nullptr) delete[] N; return pt; @@ -77,7 +77,7 @@ vpImagePoint vpNurbs::computeCurvePoint(double l_u, unsigned int l_i, unsigned i vpImagePoint vpNurbs::computeCurvePoint(double u) { - vpBasisFunction *N = NULL; + vpBasisFunction *N = nullptr; N = computeBasisFuns(u); vpImagePoint pt; @@ -93,7 +93,7 @@ vpImagePoint vpNurbs::computeCurvePoint(double u) pt.set_i(ic / wc); pt.set_j(jc / wc); - if (N != NULL) + if (N != nullptr) delete[] N; return pt; @@ -104,7 +104,7 @@ vpMatrix vpNurbs::computeCurveDers(double l_u, unsigned int l_i, unsigned int l_ std::vector &l_weights) { vpMatrix derivate(l_der + 1, 3); - vpBasisFunction **N = NULL; + vpBasisFunction **N = nullptr; N = computeDersBasisFuns(l_u, l_i, l_p, l_der, l_knots); for (unsigned int k = 0; k <= l_der; k++) { @@ -119,7 +119,7 @@ vpMatrix vpNurbs::computeCurveDers(double l_u, unsigned int l_i, unsigned int l_ } } - if (N != NULL) { + if (N != nullptr) { for (unsigned int i = 0; i <= l_der; i++) delete[] N[i]; delete[] N; @@ -130,7 +130,7 @@ vpMatrix vpNurbs::computeCurveDers(double l_u, unsigned int l_i, unsigned int l_ vpMatrix vpNurbs::computeCurveDers(double u, unsigned int der) { vpMatrix derivate(der + 1, 3); - vpBasisFunction **N = NULL; + vpBasisFunction **N = nullptr; N = computeDersBasisFuns(u, der); for (unsigned int k = 0; k <= der; k++) { @@ -144,7 +144,7 @@ vpMatrix vpNurbs::computeCurveDers(double u, unsigned int der) } } - if (N != NULL) + if (N != nullptr) delete[] N; return derivate; diff --git a/modules/tracker/me/test/testNurbs.cpp b/modules/tracker/me/test/testNurbs.cpp index 4eceb74edc..49e853206a 100644 --- a/modules/tracker/me/test/testNurbs.cpp +++ b/modules/tracker/me/test/testNurbs.cpp @@ -121,7 +121,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -134,7 +134,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; @@ -255,13 +255,13 @@ int main(int argc, const char **argv) unsigned int i = Nurbs.findSpan(5 / 2.0); std::cout << "The knot interval number for the value u = 5/2 is : " << i << std::endl; - vpBasisFunction *N = NULL; + vpBasisFunction *N = nullptr; N = Nurbs.computeBasisFuns(5 / 2.0); std::cout << "The nonvanishing basis functions N(u=5/2) are :" << std::endl; for (unsigned int j = 0; j < Nurbs.get_p() + 1; j++) std::cout << N[j].value << std::endl; - vpBasisFunction **N2 = NULL; + vpBasisFunction **N2 = nullptr; N2 = Nurbs.computeDersBasisFuns(5 / 2.0, 2); std::cout << "The first derivatives of the basis functions N'(u=5/2) are :" << std::endl; for (unsigned int j = 0; j < Nurbs.get_p() + 1; j++) @@ -345,9 +345,9 @@ int main(int argc, const char **argv) vpDisplay::getClick(I3); } - if (N != NULL) + if (N != nullptr) delete[] N; - if (N2 != NULL) { + if (N2 != nullptr) { for (int j = 0; j <= 2; j++) delete[] N2[j]; delete[] N2; diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h index 171ccfa9d0..68e1bb1902 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h @@ -145,15 +145,15 @@ class VISP_EXPORT vpTemplateTracker public: //! Default constructor. vpTemplateTracker() - : nbLvlPyr(0), l0Pyr(0), pyrInitialised(false), ptTemplate(NULL), ptTemplatePyr(NULL), ptTemplateInit(false), - templateSize(0), templateSizePyr(NULL), ptTemplateSelect(NULL), ptTemplateSelectPyr(NULL), - ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(NULL), ptTemplateSuppPyr(NULL), - ptTemplateCompo(NULL), ptTemplateCompoPyr(NULL), zoneTracked(NULL), zoneTrackedPyr(NULL), pyr_IDes(NULL), H(), - Hdesire(), HdesirePyr(NULL), HLM(), HLMdesire(), HLMdesirePyr(NULL), HLMdesireInverse(), - HLMdesireInversePyr(NULL), G(), gain(0), thresholdGradient(0), costFunctionVerification(false), blur(false), - useBrent(false), nbIterBrent(0), taillef(0), fgG(NULL), fgdG(NULL), ratioPixelIn(0), mod_i(0), mod_j(0), + : nbLvlPyr(0), l0Pyr(0), pyrInitialised(false), ptTemplate(nullptr), ptTemplatePyr(nullptr), ptTemplateInit(false), + templateSize(0), templateSizePyr(nullptr), ptTemplateSelect(nullptr), ptTemplateSelectPyr(nullptr), + ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(nullptr), ptTemplateSuppPyr(nullptr), + ptTemplateCompo(nullptr), ptTemplateCompoPyr(nullptr), zoneTracked(nullptr), zoneTrackedPyr(nullptr), pyr_IDes(nullptr), H(), + Hdesire(), HdesirePyr(nullptr), HLM(), HLMdesire(), HLMdesirePyr(nullptr), HLMdesireInverse(), + HLMdesireInversePyr(nullptr), G(), gain(0), thresholdGradient(0), costFunctionVerification(false), blur(false), + useBrent(false), nbIterBrent(0), taillef(0), fgG(nullptr), fgdG(nullptr), ratioPixelIn(0), mod_i(0), mod_j(0), nbParam(), lambdaDep(0), iterationMax(0), iterationGlobale(0), diverge(false), nbIteration(0), - useCompositionnal(false), useInverse(false), Warp(NULL), p(), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), + useCompositionnal(false), useInverse(false), Warp(nullptr), p(), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), zoneRef_() { } diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h index 11c9a13f9b..23ca9507b0 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h @@ -75,7 +75,7 @@ struct vpTemplateTrackerPoint { double *dW; double *HiG; - vpTemplateTrackerPoint() : x(0), y(0), dx(0), dy(0), val(0), dW(NULL), HiG(NULL) {} + vpTemplateTrackerPoint() : x(0), y(0), dx(0), dy(0), val(0), dW(nullptr), HiG(nullptr) {} }; /*! \struct vpTemplateTrackerPointCompo @@ -83,7 +83,7 @@ struct vpTemplateTrackerPoint { */ struct vpTemplateTrackerPointCompo { double *dW; - vpTemplateTrackerPointCompo() : dW(NULL) {} + vpTemplateTrackerPointCompo() : dW(nullptr) {} }; #ifndef DOXYGEN_SHOULD_SKIP_THIS @@ -96,7 +96,7 @@ struct vpTemplateTrackerPointSuppMIInv { double *d2W; double *d2Wx; double *d2Wy; - vpTemplateTrackerPointSuppMIInv() : et(0), ct(0), BtInit(NULL), Bt(NULL), dBt(NULL), d2W(NULL), d2Wx(NULL), d2Wy(NULL) + vpTemplateTrackerPointSuppMIInv() : et(0), ct(0), BtInit(nullptr), Bt(nullptr), dBt(nullptr), d2W(nullptr), d2Wx(nullptr), d2Wy(nullptr) { } }; diff --git a/modules/tracker/tt/src/vpTemplateTracker.cpp b/modules/tracker/tt/src/vpTemplateTracker.cpp index 6df6e7530c..7dd4e4c17c 100644 --- a/modules/tracker/tt/src/vpTemplateTracker.cpp +++ b/modules/tracker/tt/src/vpTemplateTracker.cpp @@ -41,13 +41,13 @@ #include vpTemplateTracker::vpTemplateTracker(vpTemplateTrackerWarp *_warp) - : nbLvlPyr(1), l0Pyr(0), pyrInitialised(false), evolRMS(0), x_pos(), y_pos(), evolRMS_eps(1e-4), ptTemplate(NULL), - ptTemplatePyr(NULL), ptTemplateInit(false), templateSize(0), templateSizePyr(NULL), ptTemplateSelect(NULL), - ptTemplateSelectPyr(NULL), ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(NULL), - ptTemplateSuppPyr(NULL), ptTemplateCompo(NULL), ptTemplateCompoPyr(NULL), zoneTracked(NULL), zoneTrackedPyr(NULL), - pyr_IDes(NULL), H(), Hdesire(), HdesirePyr(), HLM(), HLMdesire(), HLMdesirePyr(), HLMdesireInverse(), + : nbLvlPyr(1), l0Pyr(0), pyrInitialised(false), evolRMS(0), x_pos(), y_pos(), evolRMS_eps(1e-4), ptTemplate(nullptr), + ptTemplatePyr(nullptr), ptTemplateInit(false), templateSize(0), templateSizePyr(nullptr), ptTemplateSelect(nullptr), + ptTemplateSelectPyr(nullptr), ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(nullptr), + ptTemplateSuppPyr(nullptr), ptTemplateCompo(nullptr), ptTemplateCompoPyr(nullptr), zoneTracked(nullptr), zoneTrackedPyr(nullptr), + pyr_IDes(nullptr), H(), Hdesire(), HdesirePyr(), HLM(), HLMdesire(), HLMdesirePyr(), HLMdesireInverse(), HLMdesireInversePyr(), G(), gain(1.), thresholdGradient(40), costFunctionVerification(false), blur(true), - useBrent(false), nbIterBrent(3), taillef(7), fgG(NULL), fgdG(NULL), ratioPixelIn(0), mod_i(1), mod_j(1), nbParam(0), + useBrent(false), nbIterBrent(3), taillef(7), fgG(nullptr), fgdG(nullptr), ratioPixelIn(0), mod_i(1), mod_j(1), nbParam(0), lambdaDep(0.001), iterationMax(30), iterationGlobale(0), diverge(false), nbIteration(0), useCompositionnal(true), useInverse(false), Warp(_warp), p(0), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), zoneRef_() { @@ -169,7 +169,7 @@ void vpTemplateTracker::resetTracker() } } delete[] ptTemplatePyr; - ptTemplatePyr = NULL; + ptTemplatePyr = nullptr; } if (ptTemplateCompoPyr) { @@ -182,7 +182,7 @@ void vpTemplateTracker::resetTracker() } } delete[] ptTemplateCompoPyr; - ptTemplateCompoPyr = NULL; + ptTemplateCompoPyr = nullptr; } if (ptTemplateSuppPyr) { @@ -200,7 +200,7 @@ void vpTemplateTracker::resetTracker() } } delete[] ptTemplateSuppPyr; - ptTemplateSuppPyr = NULL; + ptTemplateSuppPyr = nullptr; } if (ptTemplateSelectPyr) { @@ -209,37 +209,37 @@ void vpTemplateTracker::resetTracker() delete[] ptTemplateSelectPyr[i]; } delete[] ptTemplateSelectPyr; - ptTemplateSelectPyr = NULL; + ptTemplateSelectPyr = nullptr; } if (templateSizePyr) { delete[] templateSizePyr; - templateSizePyr = NULL; + templateSizePyr = nullptr; } if (HdesirePyr) { delete[] HdesirePyr; - HdesirePyr = NULL; + HdesirePyr = nullptr; } if (HLMdesirePyr) { delete[] HLMdesirePyr; - HLMdesirePyr = NULL; + HLMdesirePyr = nullptr; } if (HLMdesireInversePyr) { delete[] HLMdesireInversePyr; - HLMdesireInversePyr = NULL; + HLMdesireInversePyr = nullptr; } if (zoneTrackedPyr) { delete[] zoneTrackedPyr; - zoneTrackedPyr = NULL; + zoneTrackedPyr = nullptr; } if (pyr_IDes) { delete[] pyr_IDes; - pyr_IDes = NULL; + pyr_IDes = nullptr; } } else { if (ptTemplateInit) { @@ -248,7 +248,7 @@ void vpTemplateTracker::resetTracker() delete[] ptTemplate[point].HiG; } delete[] ptTemplate; - ptTemplate = NULL; + ptTemplate = nullptr; ptTemplateInit = false; } if (ptTemplateCompo) { @@ -256,7 +256,7 @@ void vpTemplateTracker::resetTracker() delete[] ptTemplateCompo[point].dW; } delete[] ptTemplateCompo; - ptTemplateCompo = NULL; + ptTemplateCompo = nullptr; } if (ptTemplateSupp) { for (unsigned int point = 0; point < templateSize; point++) { @@ -268,12 +268,12 @@ void vpTemplateTracker::resetTracker() delete[] ptTemplateSupp[point].d2Wy; } delete[] ptTemplateSupp; - ptTemplateSupp = NULL; + ptTemplateSupp = nullptr; } if (ptTemplateSelectInit) { if (ptTemplateSelect) { delete[] ptTemplateSelect; - ptTemplateSelect = NULL; + ptTemplateSelect = nullptr; } } } @@ -519,10 +519,10 @@ void vpTemplateTracker::initPyramidal(unsigned int nbLvl, unsigned int l0) ptTemplateSuppPyr = new vpTemplateTrackerPointSuppMIInv *[nbLvlPyr]; ptTemplateCompoPyr = new vpTemplateTrackerPointCompo *[nbLvlPyr]; for (unsigned int i = 0; i < nbLvlPyr; i++) { - ptTemplatePyr[i] = NULL; - ptTemplateSuppPyr[i] = NULL; - ptTemplateSelectPyr[i] = NULL; - ptTemplateCompoPyr[i] = NULL; + ptTemplatePyr[i] = nullptr; + ptTemplateSuppPyr[i] = nullptr; + ptTemplateSelectPyr[i] = nullptr; + ptTemplateCompoPyr[i] = nullptr; } templateSizePyr = new unsigned int[nbLvlPyr]; HdesirePyr = new vpMatrix[nbLvlPyr]; diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h index 90cdc1f4f2..5bd1206e53 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h @@ -126,8 +126,8 @@ class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker // vpTemplateTrackerMI(const vpTemplateTrackerMI &) // : vpTemplateTracker(), hessianComputation(USE_HESSIEN_NORMAL), // ApproxHessian(HESSIAN_0), lambda(0), - // temp(NULL), Prt(NULL), dPrt(NULL), Pt(NULL), Pr(NULL), d2Prt(NULL), - // PrtTout(NULL), dprtemp(NULL), PrtD(NULL), dPrtD(NULL), + // temp(nullptr), Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), + // PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), // influBspline(0), bspline(0), Nc(0), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), // MI_preEstimation(0), MI_postEstimation(0), NMI_preEstimation(0), // NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false) @@ -144,8 +144,8 @@ class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker public: //! Default constructor. vpTemplateTrackerMI() - : vpTemplateTracker(), hessianComputation(USE_HESSIEN_NORMAL), ApproxHessian(HESSIAN_0), lambda(0), temp(NULL), - Prt(NULL), dPrt(NULL), Pt(NULL), Pr(NULL), d2Prt(NULL), PrtTout(NULL), dprtemp(NULL), PrtD(NULL), dPrtD(NULL), + : vpTemplateTracker(), hessianComputation(USE_HESSIEN_NORMAL), ApproxHessian(HESSIAN_0), lambda(0), temp(nullptr), + Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), influBspline(0), bspline(0), Nc(0), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), MI_preEstimation(0), MI_postEstimation(0), NMI_preEstimation(0), NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false), m_du(), m_dv(), m_A(), m_dB(), m_d2u(), m_d2v(), m_dA() diff --git a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp index dd29cc1a0c..a66ea1eb23 100644 --- a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp +++ b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp @@ -77,8 +77,8 @@ void vpTemplateTrackerMI::setBspline(const vpBsplineType &newbs) } vpTemplateTrackerMI::vpTemplateTrackerMI(vpTemplateTrackerWarp *_warp) - : vpTemplateTracker(_warp), hessianComputation(USE_HESSIEN_NORMAL), ApproxHessian(HESSIAN_NEW), lambda(0), temp(NULL), - Prt(NULL), dPrt(NULL), Pt(NULL), Pr(NULL), d2Prt(NULL), PrtTout(NULL), dprtemp(NULL), PrtD(NULL), dPrtD(NULL), + : vpTemplateTracker(_warp), hessianComputation(USE_HESSIEN_NORMAL), ApproxHessian(HESSIAN_NEW), lambda(0), temp(nullptr), + Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), influBspline(0), bspline(3), Nc(8), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), MI_preEstimation(0), MI_postEstimation(0), NMI_preEstimation(0), NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false) { diff --git a/modules/vision/include/visp3/vision/vpHomography.h b/modules/vision/include/visp3/vision/vpHomography.h index 5aa9f40b58..f7285cf638 100644 --- a/modules/vision/include/visp3/vision/vpHomography.h +++ b/modules/vision/include/visp3/vision/vpHomography.h @@ -288,7 +288,7 @@ class VISP_EXPORT vpHomography : public vpArray2D * * \return \f$\bf H^{-1}\f$ */ - vpHomography inverse(double sv_threshold = 1e-16, unsigned int *rank = NULL) const; + vpHomography inverse(double sv_threshold = 1e-16, unsigned int *rank = nullptr) const; /*! * Invert the homography. diff --git a/modules/vision/include/visp3/vision/vpKeyPoint.h b/modules/vision/include/visp3/vision/vpKeyPoint.h index e92de87162..26ffadf8c4 100644 --- a/modules/vision/include/visp3/vision/vpKeyPoint.h +++ b/modules/vision/include/visp3/vision/vpKeyPoint.h @@ -523,7 +523,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint std::vector &candidates, const std::vector &polygons, const std::vector > &roisPt, - std::vector &points, cv::Mat *descriptors = NULL); + std::vector &points, cv::Mat *descriptors = nullptr); /*! * Keep only keypoints located on faces and compute for those keypoints the 3D @@ -545,7 +545,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint std::vector &candidates, const std::vector &polygons, const std::vector > &roisPt, - std::vector &points, cv::Mat *descriptors = NULL); + std::vector &points, cv::Mat *descriptors = nullptr); /*! * Keep only keypoints located on cylinders and compute the 3D coordinates in @@ -566,7 +566,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint compute3DForPointsOnCylinders(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector &candidates, const std::vector &cylinders, const std::vector > > &vectorOfCylinderRois, - std::vector &points, cv::Mat *descriptors = NULL); + std::vector &points, cv::Mat *descriptors = nullptr); /*! * Keep only vpImagePoint located on cylinders and compute the 3D coordinates @@ -587,7 +587,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint compute3DForPointsOnCylinders(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector &candidates, const std::vector &cylinders, const std::vector > > &vectorOfCylinderRois, - std::vector &points, cv::Mat *descriptors = NULL); + std::vector &points, cv::Mat *descriptors = nullptr); /*! * Compute the pose using the correspondence between 2D points and 3D points @@ -604,7 +604,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint */ bool computePose(const std::vector &imagePoints, const std::vector &objectPoints, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, std::vector &inlierIndex, - double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = NULL); + double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = nullptr); /*! * Compute the pose using the correspondence between 2D points and 3D points @@ -619,7 +619,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * \return True if the pose has been computed, false otherwise (not enough points, or size list mismatch). */ bool computePose(const std::vector &objectVpPoints, vpHomogeneousMatrix &cMo, std::vector &inliers, - double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = NULL); + double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = nullptr); /*! * Compute the pose using the correspondence between 2D points and 3D points @@ -636,7 +636,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint */ bool computePose(const std::vector &objectVpPoints, vpHomogeneousMatrix &cMo, std::vector &inliers, std::vector &inlierIndex, double &elapsedTime, - bool (*func)(const vpHomogeneousMatrix &) = NULL); + bool (*func)(const vpHomogeneousMatrix &) = nullptr); /*! * Initialize the size of the matching image (case with a matching side by @@ -758,7 +758,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint */ void detectExtractAffine(const vpImage &I, std::vector > &listOfKeypoints, std::vector &listOfDescriptors, - std::vector > *listOfAffineI = NULL); + std::vector > *listOfAffineI = nullptr); /*! * Display the reference and the detected keypoints in the images. @@ -879,7 +879,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * cannot be extracted, we need to remove the corresponding 3D point. */ void extract(const vpImage &I, std::vector &keyPoints, cv::Mat &descriptors, - std::vector *trainPoints = NULL); + std::vector *trainPoints = nullptr); /*! * Extract the descriptors for each keypoints of the list. @@ -892,7 +892,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * cannot be extracted, we need to remove the corresponding 3D point. */ void extract(const vpImage &I_color, std::vector &keyPoints, cv::Mat &descriptors, - std::vector *trainPoints = NULL); + std::vector *trainPoints = nullptr); /*! * Extract the descriptors for each keypoints of the list. @@ -905,7 +905,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * be extracted, we need to remove the corresponding 3D point. */ void extract(const cv::Mat &matImg, std::vector &keyPoints, cv::Mat &descriptors, - std::vector *trainPoints = NULL); + std::vector *trainPoints = nullptr); /*! * Extract the descriptors for each keypoints of the list. @@ -919,7 +919,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * cannot be extracted, we need to remove the corresponding 3D point. */ void extract(const vpImage &I, std::vector &keyPoints, cv::Mat &descriptors, - double &elapsedTime, std::vector *trainPoints = NULL); + double &elapsedTime, std::vector *trainPoints = nullptr); /*! * Extract the descriptors for each keypoints of the list. @@ -933,7 +933,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * cannot be extracted, we need to remove the corresponding 3D point. */ void extract(const vpImage &I_color, std::vector &keyPoints, cv::Mat &descriptors, - double &elapsedTime, std::vector *trainPoints = NULL); + double &elapsedTime, std::vector *trainPoints = nullptr); /*! * Extract the descriptors for each keypoints of the list. @@ -947,7 +947,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * cannot be extracted, we need to remove the corresponding 3D point. */ void extract(const cv::Mat &matImg, std::vector &keyPoints, cv::Mat &descriptors, double &elapsedTime, - std::vector *trainPoints = NULL); + std::vector *trainPoints = nullptr); /*! * Get the covariance matrix when estimating the pose using the Virtual @@ -992,7 +992,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * Get the detector pointer. * \param type : Type of the detector. * - * \return The detector or NULL if the type passed in parameter does not + * \return The detector or nullptr if the type passed in parameter does not * exist. */ inline cv::Ptr getDetector(const vpFeatureDetectorType &type) const @@ -1018,7 +1018,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * Get the detector pointer. * \param name : Name of the detector. * - * \return The detector or NULL if the name passed in parameter does not + * \return The detector or nullptr if the name passed in parameter does not * exist. */ inline cv::Ptr getDetector(const std::string &name) const @@ -1048,7 +1048,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * Get the extractor pointer. * \param type : Type of the descriptor extractor. * - * \return The descriptor extractor or NULL if the name passed in parameter + * \return The descriptor extractor or nullptr if the name passed in parameter * does not exist. */ inline cv::Ptr getExtractor(const vpFeatureDescriptorType &type) const @@ -1074,7 +1074,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * Get the extractor pointer. * \param name : Name of the descriptor extractor. * - * \return The descriptor extractor or NULL if the name passed in parameter + * \return The descriptor extractor or nullptr if the name passed in parameter * does not exist. */ inline cv::Ptr getExtractor(const std::string &name) const @@ -1381,7 +1381,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * \return True if the matching and the pose estimation are OK, false otherwise. */ bool matchPoint(const vpImage &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, - bool (*func)(const vpHomogeneousMatrix &) = NULL, const vpRect &rectangle = vpRect()); + bool (*func)(const vpHomogeneousMatrix &) = nullptr, const vpRect &rectangle = vpRect()); /*! * Match keypoints detected in the image with those built in the reference @@ -1399,7 +1399,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * \return True if the matching and the pose estimation are OK, false otherwise. */ bool matchPoint(const vpImage &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, - double &error, double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = NULL, + double &error, double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = nullptr, const vpRect &rectangle = vpRect()); /*! @@ -1423,9 +1423,9 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * \return True if the object is present, false otherwise. */ bool matchPointAndDetect(const vpImage &I, vpRect &boundingBox, vpImagePoint ¢erOfGravity, - const bool isPlanarObject = true, std::vector *imPts1 = NULL, - std::vector *imPts2 = NULL, double *meanDescriptorDistance = NULL, - double *detectionScore = NULL, const vpRect &rectangle = vpRect()); + const bool isPlanarObject = true, std::vector *imPts1 = nullptr, + std::vector *imPts2 = nullptr, double *meanDescriptorDistance = nullptr, + double *detectionScore = nullptr, const vpRect &rectangle = vpRect()); /*! * Match keypoints detected in the image with those built in the reference @@ -1448,7 +1448,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint */ bool matchPointAndDetect(const vpImage &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, double &error, double &elapsedTime, vpRect &boundingBox, vpImagePoint ¢erOfGravity, - bool (*func)(const vpHomogeneousMatrix &) = NULL, const vpRect &rectangle = vpRect()); + bool (*func)(const vpHomogeneousMatrix &) = nullptr, const vpRect &rectangle = vpRect()); /*! * Match keypoints detected in the image with those built in the reference @@ -1495,7 +1495,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * \return True if the matching and the pose estimation are OK, false otherwise. */ bool matchPoint(const vpImage &I_color, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, - bool (*func)(const vpHomogeneousMatrix &) = NULL, const vpRect &rectangle = vpRect()); + bool (*func)(const vpHomogeneousMatrix &) = nullptr, const vpRect &rectangle = vpRect()); /*! * Match keypoints detected in the image with those built in the reference @@ -1513,7 +1513,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint * \return True if the matching and the pose estimation are OK, false otherwise. */ bool matchPoint(const vpImage &I_color, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, - double &error, double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = NULL, + double &error, double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &) = nullptr, const vpRect &rectangle = vpRect()); /*! @@ -1735,7 +1735,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint m_useKnn = true; #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000) - if (m_matcher != NULL && m_matcherName == "BruteForce") { + if (m_matcher != nullptr && m_matcherName == "BruteForce") { // if a matcher is already initialized, disable the crossCheck // because it will not work with knnMatch m_matcher->set("crossCheck", false); @@ -1746,7 +1746,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint m_useKnn = false; #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000) - if (m_matcher != NULL && m_matcherName == "BruteForce") { + if (m_matcher != nullptr && m_matcherName == "BruteForce") { // if a matcher is already initialized, set the crossCheck mode if // necessary m_matcher->set("crossCheck", m_useBruteForceCrossCheck); @@ -1909,10 +1909,10 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint { // Only available with BruteForce and with k=1 (i.e not used with a // ratioDistanceThreshold method) - if (m_matcher != NULL && !m_useKnn && m_matcherName == "BruteForce") { + if (m_matcher != nullptr && !m_useKnn && m_matcherName == "BruteForce") { m_matcher->set("crossCheck", useCrossCheck); } - else if (m_matcher != NULL && m_useKnn && m_matcherName == "BruteForce") { + else if (m_matcher != nullptr && m_useKnn && m_matcherName == "BruteForce") { std::cout << "Warning, you try to set the crossCheck parameter with a " "BruteForce matcher but knn is enabled"; std::cout << " (the filtering method uses a ratio constraint)" << std::endl; diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index abd2644b59..fbc0101b5c 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -181,7 +181,7 @@ class VISP_EXPORT vpPose * has the smallest residual. * - vpPose::RANSAC: Robust Ransac aproach (doesn't need an initialization) */ - bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneousMatrix &) = NULL); + bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneousMatrix &) = nullptr); /*! * @brief Method that first computes the pose \b cMo using the linear approaches of Dementhon and Lagrange @@ -254,7 +254,7 @@ class VISP_EXPORT vpPose * \param p_d: if different from null, it will be set to equal the d coefficient of the potential plan. * \return true if points are coplanar false otherwise. */ - bool coplanar(int &coplanar_plane_type, double *p_a = NULL, double *p_b = NULL, double *p_c = NULL, double *p_d = NULL); + bool coplanar(int &coplanar_plane_type, double *p_a = nullptr, double *p_b = nullptr, double *p_c = nullptr, double *p_d = nullptr); /*! * Display the coordinates of the points in the image plane that are used to @@ -286,14 +286,14 @@ class VISP_EXPORT vpPose * Compute the pose of a planar object using Lagrange approach. * * \param cMo : Estimated pose. No initialisation is requested to estimate cMo. - * \param p_isPlan : if different from NULL, indicates if the object is planar or not. - * \param p_a : if different from NULL, the a coefficient of the plan formed by the points. - * \param p_b : if different from NULL, the b coefficient of the plan formed by the points. - * \param p_c : if different from NULL, the c coefficient of the plan formed by the points. - * \param p_d : if different from NULL, the d coefficient of the plan formed by the points. + * \param p_isPlan : if different from nullptr, indicates if the object is planar or not. + * \param p_a : if different from nullptr, the a coefficient of the plan formed by the points. + * \param p_b : if different from nullptr, the b coefficient of the plan formed by the points. + * \param p_c : if different from nullptr, the c coefficient of the plan formed by the points. + * \param p_d : if different from nullptr, the d coefficient of the plan formed by the points. */ - void poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan = NULL, double *p_a = NULL, double *p_b = NULL, - double *p_c = NULL, double *p_d = NULL); + void poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan = nullptr, double *p_a = nullptr, double *p_b = nullptr, + double *p_c = nullptr, double *p_d = nullptr); /*! * Compute the pose of a non planar object using Lagrange approach. @@ -324,7 +324,7 @@ class VISP_EXPORT vpPose * The number of threads used can then be set with setNbParallelRansacThreads(). * Filter flag can be used with setRansacFilterFlag(). */ - bool poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneousMatrix &) = NULL); + bool poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneousMatrix &) = nullptr); /*! * Compute the pose using virtual visual servoing approach and @@ -522,7 +522,7 @@ class VISP_EXPORT vpPose static bool computePlanarObjectPoseFromRGBD(const vpImage &depthMap, const std::vector &corners, const vpCameraParameters &colorIntrinsics, const std::vector &point3d, vpHomogeneousMatrix &cMo, - double *confidence_index = NULL); + double *confidence_index = nullptr); /*! * Compute the pose of multiple planar object from corresponding 2D-3D point coordinates and depth map. @@ -560,7 +560,7 @@ class VISP_EXPORT vpPose const std::vector > &corners, const vpCameraParameters &colorIntrinsics, const std::vector > &point3d, - vpHomogeneousMatrix &cMo, double *confidence_index = NULL, + vpHomogeneousMatrix &cMo, double *confidence_index = nullptr, bool coplanar_points = true); /*! @@ -645,7 +645,7 @@ class VISP_EXPORT vpPose const unsigned int &numberOfInlierToReachAConsensus, const double &threshold, unsigned int &ninliers, std::vector &listInliers, vpHomogeneousMatrix &cMo, const int &maxNbTrials = 10000, bool useParallelRansac = true, unsigned int nthreads = 0, - bool (*func)(const vpHomogeneousMatrix &) = NULL); + bool (*func)(const vpHomogeneousMatrix &) = nullptr); /*! * Carries out the camera pose the image of a rectangle and diff --git a/modules/vision/include/visp3/vision/vpPoseFeatures.h b/modules/vision/include/visp3/vision/vpPoseFeatures.h index 5a70f55e9c..0a621cccab 100644 --- a/modules/vision/include/visp3/vision/vpPoseFeatures.h +++ b/modules/vision/include/visp3/vision/vpPoseFeatures.h @@ -573,7 +573,7 @@ class VISP_EXPORT vpPoseFeatures { FeatureType *desiredFeature; FirstParamType firstParam; - vpDuo() : desiredFeature(NULL), firstParam() { } + vpDuo() : desiredFeature(nullptr), firstParam() { } }; template struct vpTrio @@ -582,7 +582,7 @@ class VISP_EXPORT vpPoseFeatures FirstParamType firstParam; SecondParamType secondParam; - vpTrio() : desiredFeature(NULL), firstParam(), secondParam() { } + vpTrio() : desiredFeature(nullptr), firstParam(), secondParam() { } }; #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/vision/src/homography-estimation/vpHomography.cpp b/modules/vision/src/homography-estimation/vpHomography.cpp index 0e88aae60c..ea60522fea 100644 --- a/modules/vision/src/homography-estimation/vpHomography.cpp +++ b/modules/vision/src/homography-estimation/vpHomography.cpp @@ -125,7 +125,7 @@ vpHomography vpHomography::inverse(double sv_threshold, unsigned int *rank) cons vpMatrix M = (*this).convert(); vpMatrix Minv; unsigned int r = M.pseudoInverse(Minv, sv_threshold); - if (rank != NULL) { + if (rank != nullptr) { *rank = r; } diff --git a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp index 891e494cf2..dfb1ad5a6d 100644 --- a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp @@ -293,7 +293,7 @@ bool vpHomography::ransac(const std::vector &xb, const std::vector best_consensus; std::vector cur_consensus; diff --git a/modules/vision/src/key-point/vpKeyPoint.cpp b/modules/vision/src/key-point/vpKeyPoint.cpp index ce49956d51..994b18ec01 100644 --- a/modules/vision/src/key-point/vpKeyPoint.cpp +++ b/modules/vision/src/key-point/vpKeyPoint.cpp @@ -485,7 +485,7 @@ void vpKeyPoint::compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, co vpKeyPoint::compute3D(it2->first, roisPt[cpt1], cam, cMo, pt); points.push_back(pt); - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.push_back(descriptors->row((int)it2->second)); } @@ -498,7 +498,7 @@ void vpKeyPoint::compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, co } } - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.copyTo(*descriptors); } } @@ -531,7 +531,7 @@ void vpKeyPoint::compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, co vpKeyPoint::compute3D(it2->first, roisPt[cpt1], cam, cMo, pt); points.push_back(pt); - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.push_back(descriptors->row((int)it2->second)); } @@ -590,7 +590,7 @@ void vpKeyPoint::compute3DForPointsOnCylinders( pt.setWorldCoordinates(point_obj); points.push_back(cv::Point3f((float)pt.get_oX(), (float)pt.get_oY(), (float)pt.get_oZ())); - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.push_back(descriptors->row((int)cpt_keypoint)); } @@ -601,7 +601,7 @@ void vpKeyPoint::compute3DForPointsOnCylinders( } } - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.copyTo(*descriptors); } } @@ -650,7 +650,7 @@ void vpKeyPoint::compute3DForPointsOnCylinders( pt.setWorldCoordinates(point_obj); points.push_back(pt); - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.push_back(descriptors->row((int)cpt_keypoint)); } @@ -661,7 +661,7 @@ void vpKeyPoint::compute3DForPointsOnCylinders( } } - if (descriptors != NULL) { + if (descriptors != nullptr) { desc.copyTo(*descriptors); } } @@ -738,7 +738,7 @@ bool vpKeyPoint::computePose(const std::vector &imagePoints, const vpThetaUVector thetaUVector(rvec.at(0), rvec.at(1), rvec.at(2)); cMo = vpHomogeneousMatrix(translationVec, thetaUVector); - if (func != NULL) { + if (func != nullptr) { // Check the final pose returned by solvePnPRansac to discard // solutions which do not respect the pose criterion. if (!func(cMo)) { @@ -809,7 +809,7 @@ bool vpKeyPoint::computePose(const std::vector &objectVpPoints, vpHomog return false; } - // if(func != NULL && isRansacPoseEstimationOk) { + // if(func != nullptr && isRansacPoseEstimationOk) { // //Check the final pose returned by the Ransac VVS pose estimation as // in rare some cases // //we can converge toward a final cMo that does not respect the pose @@ -1088,7 +1088,7 @@ void vpKeyPoint::displayMatching(const vpImage &IRef, vpImage queryImageKeyPoints; @@ -1115,7 +1115,7 @@ void vpKeyPoint::displayMatching(const vpImage &IRef, vpImage queryImageKeyPoints; @@ -1142,7 +1142,7 @@ void vpKeyPoint::displayMatching(const vpImage &IRef, vpImage &I unsigned int lineThickness, const vpColor &color) { bool randomColor = (color == vpColor::none); - srand((unsigned int)time(NULL)); + srand((unsigned int)time(nullptr)); vpColor currentColor = color; std::vector queryImageKeyPoints; @@ -1440,7 +1440,7 @@ void vpKeyPoint::extract(const cv::Mat &matImg, std::vector &keyPo if (first) { first = false; // Check if we have 3D object points information - if (trainPoints != NULL && !trainPoints->empty()) { + if (trainPoints != nullptr && !trainPoints->empty()) { // Copy the input list of keypoints, keypoints that cannot be computed // are removed in the function compute std::vector keyPoints_tmp = keyPoints; @@ -1499,7 +1499,7 @@ void vpKeyPoint::extract(const cv::Mat &matImg, std::vector &keyPo cv::Mat descriptors_tmp; for (std::vector::const_iterator it = keyPoints.begin(); it != keyPoints.end(); ++it) { if (mapOfKeypointHashes.find(myKeypointHash(*it)) != mapOfKeypointHashes.end()) { - if (trainPoints != NULL && !trainPoints->empty()) { + if (trainPoints != nullptr && !trainPoints->empty()) { trainPoints_tmp.push_back((*trainPoints)[mapOfKeypointHashes[myKeypointHash(*it)]]); } @@ -1509,7 +1509,7 @@ void vpKeyPoint::extract(const cv::Mat &matImg, std::vector &keyPo } } - if (trainPoints != NULL) { + if (trainPoints != nullptr) { // Copy trainPoints_tmp to m_trainPoints *trainPoints = trainPoints_tmp; } @@ -1733,7 +1733,7 @@ void vpKeyPoint::initDetector(const std::string &detectorName) #if (VISP_HAVE_OPENCV_VERSION < 0x030000) m_detectors[detectorName] = cv::FeatureDetector::create(detectorName); - if (m_detectors[detectorName] == NULL) { + if (m_detectors[detectorName] == nullptr) { std::stringstream ss_msg; ss_msg << "Fail to initialize the detector: " << detectorName << " or it is not available in OpenCV version: " << std::hex << VISP_HAVE_OPENCV_VERSION << "."; @@ -2249,7 +2249,7 @@ void vpKeyPoint::initMatcher(const std::string &matcherName) } #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000) - if (m_matcher != NULL && !m_useKnn && matcherName == "BruteForce") { + if (m_matcher != nullptr && !m_useKnn && matcherName == "BruteForce") { m_matcher->set("crossCheck", m_useBruteForceCrossCheck); } #endif @@ -3268,7 +3268,7 @@ bool vpKeyPoint::matchPointAndDetect(const vpImage &I, vpRect &bo std::vector *imPts1, std::vector *imPts2, double *meanDescriptorDistance, double *detectionScore, const vpRect &rectangle) { - if (imPts1 != NULL && imPts2 != NULL) { + if (imPts1 != nullptr && imPts2 != nullptr) { imPts1->clear(); imPts2->clear(); } @@ -3283,10 +3283,10 @@ bool vpKeyPoint::matchPointAndDetect(const vpImage &I, vpRect &bo meanDescriptorDistanceTmp /= (double)m_filteredMatches.size(); double score = (double)m_filteredMatches.size() / meanDescriptorDistanceTmp; - if (meanDescriptorDistance != NULL) { + if (meanDescriptorDistance != nullptr) { *meanDescriptorDistance = meanDescriptorDistanceTmp; } - if (detectionScore != NULL) { + if (detectionScore != nullptr) { *detectionScore = score; } @@ -3323,11 +3323,11 @@ bool vpKeyPoint::matchPointAndDetect(const vpImage &I, vpRect &bo if (reprojectionError < 6.0) { inliers.push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x)); - if (imPts1 != NULL) { + if (imPts1 != nullptr) { imPts1->push_back(vpImagePoint((double)points1[i].y, (double)points1[i].x)); } - if (imPts2 != NULL) { + if (imPts2 != nullptr) { imPts2->push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x)); } } @@ -3341,11 +3341,11 @@ bool vpKeyPoint::matchPointAndDetect(const vpImage &I, vpRect &bo if (fundamentalInliers.at((int)i, 0)) { inliers.push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x)); - if (imPts1 != NULL) { + if (imPts1 != nullptr) { imPts1->push_back(vpImagePoint((double)points1[i].y, (double)points1[i].x)); } - if (imPts2 != NULL) { + if (imPts2 != nullptr) { imPts2->push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x)); } } @@ -3449,7 +3449,7 @@ void vpKeyPoint::detectExtractAffine(const vpImage &I, affineSkew(t, phi, timg, mask, Ai); - if (listOfAffineI != NULL) { + if (listOfAffineI != nullptr) { cv::Mat img_disp; bitwise_and(mask, timg, img_disp); vpImage tI; @@ -3502,7 +3502,7 @@ void vpKeyPoint::detectExtractAffine(const vpImage &I, listOfKeypoints.resize(listOfAffineParams.size()); listOfDescriptors.resize(listOfAffineParams.size()); - if (listOfAffineI != NULL) { + if (listOfAffineI != nullptr) { listOfAffineI->resize(listOfAffineParams.size()); } @@ -3518,7 +3518,7 @@ void vpKeyPoint::detectExtractAffine(const vpImage &I, affineSkew(listOfAffineParams[(size_t)cpt].first, listOfAffineParams[(size_t)cpt].second, timg, mask, Ai); - if (listOfAffineI != NULL) { + if (listOfAffineI != nullptr) { cv::Mat img_disp; bitwise_and(mask, timg, img_disp); vpImage tI; diff --git a/modules/vision/src/pose-estimation/vpPose.cpp b/modules/vision/src/pose-estimation/vpPose.cpp index 0d281d338b..b81f76f9bd 100644 --- a/modules/vision/src/pose-estimation/vpPose.cpp +++ b/modules/vision/src/pose-estimation/vpPose.cpp @@ -261,21 +261,21 @@ bool vpPose::coplanar(int &coplanar_plane_type, double *p_a, double *p_b, double vpDEBUG_TRACE(10, " points are coplanar "); // vpTRACE(" points are coplanar ") ; - // If the points are coplanar and the input/output parameters are different from NULL, + // If the points are coplanar and the input/output parameters are different from nullptr, // getting the values of the plan coefficient and storing in the input/output parameters - if (p_a != NULL) { + if (p_a != nullptr) { *p_a = a; } - if (p_b != NULL) { + if (p_b != nullptr) { *p_b = b; } - if (p_c != NULL) { + if (p_c != nullptr) { *p_c = c; } - if (p_d != NULL) { + if (p_d != nullptr) { *p_d = d; } diff --git a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp index 33dbe8eea7..56f5bbd847 100644 --- a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp @@ -252,9 +252,9 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * double a, b, c, d; // Checking if coplanar has already been called and if the plan coefficients have been given - if ((p_isPlan != NULL) && (p_a != NULL) && (p_b != NULL) && (p_c != NULL) && (p_d != NULL)) { + if ((p_isPlan != nullptr) && (p_a != nullptr) && (p_b != nullptr) && (p_c != nullptr) && (p_d != nullptr)) { if (*p_isPlan) { - // All the pointers towards the plan coefficients are different from NULL => using them in the rest of the method + // All the pointers towards the plan coefficients are different from nullptr => using them in the rest of the method a = *p_a; b = *p_b; c = *p_c; @@ -266,7 +266,7 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * } } else { - // At least one of the coefficient is a NULL pointer => calling coplanar by ourselves + // At least one of the coefficient is a nullptr pointer => calling coplanar by ourselves int coplanarType; bool areCoplanar = coplanar(coplanarType, &a, &b, &c, &d); if (!areCoplanar) { diff --git a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp index 56d813fead..3dbf651bf0 100644 --- a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp @@ -155,7 +155,7 @@ bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, con point3d.size(), corners.size())); } std::vector pose_points; - if (confidence_index != NULL) { + if (confidence_index != nullptr) { *confidence_index = 0.0; } @@ -223,7 +223,7 @@ bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, con vpPose pose; pose.addPoints(pose_points); if (pose.computePose(vpPose::VIRTUAL_VS, cMo)) { - if (confidence_index != NULL) { + if (confidence_index != nullptr) { *confidence_index = std::min(1.0, normalized_weights * static_cast(nb_points_3d) / polygon.getArea()); } return true; @@ -247,7 +247,7 @@ bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, point3d.size(), corners.size())); } std::vector pose_points; - if (confidence_index != NULL) { + if (confidence_index != nullptr) { *confidence_index = 0.0; } @@ -418,7 +418,7 @@ bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, vpPose pose; pose.addPoints(pose_points); if (pose.computePose(vpPose::VIRTUAL_VS, cMo)) { - if (confidence_index != NULL) { + if (confidence_index != nullptr) { *confidence_index = std::min(1.0, normalized_weights * static_cast(nb_points_3d) / totalArea); } return true; diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index cd470e4ec4..7008fe4832 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -220,7 +220,7 @@ bool vpPose::vpRansacFunctor::poseRansacImpl() // Filter the pose using some criterion (orientation angles, // translations, etc.) bool isPoseValid = true; - if (m_func != NULL) { + if (m_func != nullptr) { isPoseValid = m_func(cMo_tmp); if (isPoseValid) { m_cMo = cMo_tmp; @@ -378,7 +378,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo int splitTrials = ransacMaxTrials / nbThreads; for (size_t i = 0; i < (size_t)nbThreads; i++) { - unsigned int initial_seed = (unsigned int)i; //((unsigned int) time(NULL) ^ i); + unsigned int initial_seed = (unsigned int)i; //((unsigned int) time(nullptr) ^ i); if (i < (size_t)nbThreads - 1) { ransacWorkers.emplace_back(cMo, ransacNbInlierConsensus, splitTrials, ransacThreshold, initial_seed, checkDegeneratePoints, listOfUniquePoints, func); @@ -476,7 +476,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo // In some rare cases, the final pose could not respect the pose // criterion even if the 4 minimal points picked respect the pose // criterion. - if (func != NULL && !func(cMo)) { + if (func != nullptr && !func(cMo)) { return false; } diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp index 4234bd2f76..8c0391e565 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp @@ -120,7 +120,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, use_parallel_ransac = true; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -133,7 +133,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp index 1587b3c40f..1040f85c2f 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp @@ -114,7 +114,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -127,7 +127,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp index 012ed3ed94..55282dc3f3 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp @@ -116,7 +116,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -129,7 +129,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp index 2a8297ce4a..d896830b4e 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp @@ -117,7 +117,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -130,7 +130,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp index 3fe0ee74cb..d8fd45b188 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp @@ -110,7 +110,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -123,7 +123,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp index 611e1f5b15..e1143220c8 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp @@ -108,7 +108,7 @@ bool getOptions(int argc, const char **argv, std::string &opath, const std::stri opath = optarg_; break; case 'h': - usage(argv[0], NULL, opath, user); + usage(argv[0], nullptr, opath, user); return false; break; @@ -123,7 +123,7 @@ bool getOptions(int argc, const char **argv, std::string &opath, const std::stri if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL, opath, user); + usage(argv[0], nullptr, opath, user); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp index 3771d0c945..7240c1e375 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp @@ -113,7 +113,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) display = false; break; case 'h': - usage(argv[0], NULL); + usage(argv[0], nullptr); return false; break; @@ -126,7 +126,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) if ((c == 1) || (c == -1)) { // standalone param or error - usage(argv[0], NULL); + usage(argv[0], nullptr); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument " << optarg_ << std::endl << std::endl; return false; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h index 2517506534..0881c74a3e 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h @@ -140,7 +140,7 @@ class vpMoment; * //more than a shortcut to the vpMomentObject) * bm.linkTo(mdb); //add basic moment to moment database * - * vpFeatureMomentBasic fmb(mdb,0,0,1,NULL); + * vpFeatureMomentBasic fmb(mdb,0,0,1,nullptr); * * //update and compute the vpMoment BEFORE doing any operations with vpFeatureMoment * bm.update(obj); @@ -169,8 +169,8 @@ class VISP_EXPORT vpFeatureMoment : public vpBasicFeature // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpFeatureMoment(const vpFeatureMoment &fm) - // : vpBasicFeature(), moment(NULL), moments(fm.moments), - // featureMomentsDataBase(NULL), + // : vpBasicFeature(), moment(nullptr), moments(fm.moments), + // featureMomentsDataBase(nullptr), // interaction_matrices(), A(0), B(0), C(0) // { // throw vpException(vpException::functionNotImplementedError, "Not @@ -198,8 +198,8 @@ class VISP_EXPORT vpFeatureMoment : public vpBasicFeature * number of lines by this parameter. */ vpFeatureMoment(vpMomentDatabase &data_base, double A_ = 0.0, double B_ = 0.0, double C_ = 0.0, - vpFeatureMomentDatabase *featureMoments = NULL, unsigned int nbmatrices = 1) - : vpBasicFeature(), moment(NULL), moments(data_base), featureMomentsDataBase(featureMoments), + vpFeatureMomentDatabase *featureMoments = nullptr, unsigned int nbmatrices = 1) + : vpBasicFeature(), moment(nullptr), moments(data_base), featureMomentsDataBase(featureMoments), interaction_matrices(nbmatrices), A(A_), B(B_), C(C_), _name() { } @@ -265,12 +265,12 @@ class VISP_EXPORT vpMomentGenericFeature : public vpFeatureMoment /*! * No specific moment name. */ - const char *momentName() const { return NULL; } + const char *momentName() const { return nullptr; } /*! * No specific feature name. */ - virtual const char *name() const { return NULL; } + virtual const char *name() const { return nullptr; } }; #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h index f8214c084d..0c5966cf5d 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h @@ -110,7 +110,7 @@ class VISP_EXPORT vpFeatureMomentAlpha : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentAlpha(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 1) { } diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h index 08d16431f9..cee3586df5 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h @@ -65,7 +65,7 @@ class VISP_EXPORT vpFeatureMomentArea : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentArea(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 1) { } diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h index 4cc159960b..dfaf6fc045 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h @@ -91,7 +91,7 @@ class VISP_EXPORT vpFeatureMomentAreaNormalized : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentAreaNormalized(vpMomentDatabase &database, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(database, A_, B_, C_, featureMoments, 1) { } void compute_interaction() override; @@ -186,7 +186,7 @@ class VISP_EXPORT vpFeatureMomentAreaNormalized : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentAreaNormalized(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 1) { } void compute_interaction() override; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h index 9a8855bb27..02195d8ea5 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h @@ -80,7 +80,7 @@ class VISP_EXPORT vpFeatureMomentBasic : public vpFeatureMoment public: vpFeatureMomentBasic(vpMomentDatabase &moments, double A, double B, double C, - vpFeatureMomentDatabase *featureMoments = NULL); + vpFeatureMomentDatabase *featureMoments = nullptr); void compute_interaction() override; #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h index 466fd87c58..0f5b5da2de 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h @@ -100,7 +100,7 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentCInvariant(vpMomentDatabase &moments, double A, double B, double C, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(moments, A, B, C, featureMoments, 16) { } void compute_interaction() override; @@ -238,7 +238,7 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentCInvariant(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 16), LI(16) { } diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h index d48712d45d..8762be8960 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h @@ -84,7 +84,7 @@ class VISP_EXPORT vpFeatureMomentCentered : public vpFeatureMoment public: vpFeatureMomentCentered(vpMomentDatabase &moments, double A, double B, double C, - vpFeatureMomentDatabase *featureMoments = NULL); + vpFeatureMomentDatabase *featureMoments = nullptr); void compute_interaction() override; #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h index c4856154eb..858f5b1a93 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h @@ -155,7 +155,7 @@ class VISP_EXPORT vpFeatureMomentDatabase struct vpCmpStr_t { bool operator()(const char *a, const char *b) const { return std::strcmp(a, b) < 0; } - char *operator=(const char *) { return NULL; } // Only to avoid a warning under Visual with /Wall flag + char *operator=(const char *) { return nullptr; } // Only to avoid a warning under Visual with /Wall flag }; std::map featureMomentsDataBase; void add(vpFeatureMoment &featureMoment, char *name); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h index 28c148890a..8958915f68 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h @@ -157,7 +157,7 @@ class VISP_EXPORT vpFeatureMomentGravityCenter : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentGravityCenter(vpMomentDatabase &database, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(database, A_, B_, C_, featureMoments, 2) { } @@ -229,7 +229,7 @@ class VISP_EXPORT vpFeatureMomentGravityCenter : public vpFeatureMoment * \param featureMoments : Feature database. */ vpFeatureMomentGravityCenter(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 2) { } diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h index eb408e2b97..c75dc0d401 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h @@ -98,7 +98,7 @@ class VISP_EXPORT vpFeatureMomentGravityCenterNormalized : public vpFeatureMomen * \param featureMoments : Feature database. */ vpFeatureMomentGravityCenterNormalized(vpMomentDatabase &database, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(database, A_, B_, C_, featureMoments, 2) { } void compute_interaction() override; @@ -252,7 +252,7 @@ class VISP_EXPORT vpFeatureMomentGravityCenterNormalized : public vpFeatureMomen * \param featureMoments : Feature database. */ vpFeatureMomentGravityCenterNormalized(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments = NULL) + vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 2) { } void compute_interaction() override; diff --git a/modules/visual_features/src/visual-feature/vpBasicFeature.cpp b/modules/visual_features/src/visual-feature/vpBasicFeature.cpp index cb3b1a6be3..1f219c43b9 100644 --- a/modules/visual_features/src/visual-feature/vpBasicFeature.cpp +++ b/modules/visual_features/src/visual-feature/vpBasicFeature.cpp @@ -55,16 +55,16 @@ const unsigned int vpBasicFeature::FEATURE_LINE[32] = { /*! Default constructor. */ -vpBasicFeature::vpBasicFeature() : s(), dim_s(0), flags(NULL), nbParameters(0), deallocate(vpBasicFeature::user) {} +vpBasicFeature::vpBasicFeature() : s(), dim_s(0), flags(nullptr), nbParameters(0), deallocate(vpBasicFeature::user) {} /*! Destructor that free allocated memory. */ vpBasicFeature::~vpBasicFeature() { - if (flags != NULL) { + if (flags != nullptr) { delete[] flags; - flags = NULL; + flags = nullptr; } } @@ -72,7 +72,7 @@ vpBasicFeature::~vpBasicFeature() Copy constructor. */ vpBasicFeature::vpBasicFeature(const vpBasicFeature &f) - : s(), dim_s(0), flags(NULL), nbParameters(0), deallocate(vpBasicFeature::user) + : s(), dim_s(0), flags(nullptr), nbParameters(0), deallocate(vpBasicFeature::user) { *this = f; } @@ -128,7 +128,7 @@ vpColVector vpBasicFeature::get_s(unsigned int select) const void vpBasicFeature::resetFlags() { - if (flags != NULL) { + if (flags != nullptr) { for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; } @@ -138,7 +138,7 @@ void vpBasicFeature::resetFlags() //! interaction matrix without having updated the feature. void vpBasicFeature::setFlags() { - if (flags != NULL) { + if (flags != nullptr) { for (unsigned int i = 0; i < nbParameters; i++) flags[i] = true; } diff --git a/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp b/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp index 5cb0cb5a05..bc0c494552 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp @@ -77,7 +77,7 @@ void vpFeatureDepth::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp index fe758ff51b..025110b466 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp @@ -68,7 +68,7 @@ void vpFeatureEllipse::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeatureLine.cpp b/modules/visual_features/src/visual-feature/vpFeatureLine.cpp index f225cbf4ed..f7d30b06d3 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLine.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLine.cpp @@ -81,7 +81,7 @@ void vpFeatureLine::init() // s[0] = rho // s[1] = theta s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp index c801bf45be..7c48ad5000 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp @@ -55,7 +55,7 @@ */ void vpFeatureLuminance::init() { - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; @@ -84,7 +84,7 @@ void vpFeatureLuminance::init(unsigned int _nbr, unsigned int _nbc, double _Z) s.resize(dim_s); - if (pixInfo != NULL) + if (pixInfo != nullptr) delete[] pixInfo; pixInfo = new vpLuminance[dim_s]; @@ -95,11 +95,11 @@ void vpFeatureLuminance::init(unsigned int _nbr, unsigned int _nbc, double _Z) /*! Default constructor that build a visual feature. */ -vpFeatureLuminance::vpFeatureLuminance() : Z(1), nbr(0), nbc(0), bord(10), pixInfo(NULL), firstTimeIn(0), cam() +vpFeatureLuminance::vpFeatureLuminance() : Z(1), nbr(0), nbc(0), bord(10), pixInfo(nullptr), firstTimeIn(0), cam() { nbParameters = 1; dim_s = 0; - flags = NULL; + flags = nullptr; init(); } @@ -108,7 +108,7 @@ vpFeatureLuminance::vpFeatureLuminance() : Z(1), nbr(0), nbc(0), bord(10), pixIn Copy constructor. */ vpFeatureLuminance::vpFeatureLuminance(const vpFeatureLuminance &f) - : vpBasicFeature(f), Z(1), nbr(0), nbc(0), bord(10), pixInfo(NULL), firstTimeIn(0), cam() + : vpBasicFeature(f), Z(1), nbr(0), nbc(0), bord(10), pixInfo(nullptr), firstTimeIn(0), cam() { *this = f; } @@ -137,7 +137,7 @@ vpFeatureLuminance &vpFeatureLuminance::operator=(const vpFeatureLuminance &f) */ vpFeatureLuminance::~vpFeatureLuminance() { - if (pixInfo != NULL) + if (pixInfo != nullptr) delete[] pixInfo; } diff --git a/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp b/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp index 5f7e9515af..490f4cc90f 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp @@ -56,7 +56,7 @@ void vpFeatureMoment::init() * vpMoment associated to it. This partly explains why vpFeatureMomentBasic * cannot be used directly as a visual feature. */ - if (this->moment != NULL) + if (this->moment != nullptr) dim_s = (unsigned int)this->moment->get().size(); else dim_s = 0; @@ -68,7 +68,7 @@ void vpFeatureMoment::init() for (unsigned int i = 0; i < dim_s; i++) s[i] = 0; - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; @@ -150,14 +150,14 @@ void vpFeatureMoment::update(double A_, double B_, double C_) this->B = B_; this->C = C_; - if (moment == NULL) { + if (moment == nullptr) { bool found; this->moment = &(moments.get(momentName(), found)); if (!found) throw vpException(vpException::notInitialized, "Moment not found for feature"); } nbParameters = 1; - if (this->moment != NULL) { + if (this->moment != nullptr) { dim_s = (unsigned int)this->moment->get().size(); s.resize(dim_s); @@ -165,7 +165,7 @@ void vpFeatureMoment::update(double A_, double B_, double C_) for (unsigned int i = 0; i < dim_s; i++) s[i] = this->moment->get()[i]; - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp b/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp index d22d11a691..2ccaf8150f 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp @@ -71,7 +71,7 @@ void vpFeaturePoint::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp b/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp index 5eceae66b5..5b667d40f5 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp @@ -65,7 +65,7 @@ void vpFeaturePoint3D::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp b/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp index c5f924c844..57534d3ec1 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp @@ -77,7 +77,7 @@ void vpFeaturePointPolar::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp b/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp index 7a724ab5a5..d0b3f76ec9 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp @@ -61,7 +61,7 @@ void vpFeatureSegment::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp b/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp index a11dfc298a..7c3c348fec 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp @@ -68,7 +68,7 @@ void vpFeatureThetaU::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp b/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp index afb2451846..1a1063913f 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp @@ -69,7 +69,7 @@ void vpFeatureTranslation::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; @@ -587,7 +587,7 @@ void vpFeatureTranslation::print(unsigned int select) const */ vpFeatureTranslation *vpFeatureTranslation::duplicate() const { - vpFeatureTranslation *feature = NULL; + vpFeatureTranslation *feature = nullptr; if (translation == cdMc) feature = new vpFeatureTranslation(cdMc); if (translation == cMo) diff --git a/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp b/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp index e682e8b29c..3875e5677a 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp @@ -67,7 +67,7 @@ void vpFeatureVanishingPoint::init() // memory allocation s.resize(dim_s); - if (flags == NULL) + if (flags == nullptr) flags = new bool[nbParameters]; for (unsigned int i = 0; i < nbParameters; i++) flags[i] = false; diff --git a/modules/vs/src/vpServo.cpp b/modules/vs/src/vpServo.cpp index 50e67df55a..ddd180e656 100644 --- a/modules/vs/src/vpServo.cpp +++ b/modules/vs/src/vpServo.cpp @@ -112,14 +112,14 @@ void vpServo::kill() for (std::list::iterator it = featureList.begin(); it != featureList.end(); ++it) { if ((*it)->getDeallocate() == vpBasicFeature::vpServo) { delete (*it); - (*it) = NULL; + (*it) = nullptr; } } // desired list for (std::list::iterator it = desiredFeatureList.begin(); it != desiredFeatureList.end(); ++it) { if ((*it)->getDeallocate() == vpBasicFeature::vpServo) { delete (*it); - (*it) = NULL; + (*it) = nullptr; } } diff --git a/modules/vs/test/visual-feature/testFeatureSegment.cpp b/modules/vs/test/visual-feature/testFeatureSegment.cpp index 5d5bd4935f..b5b260547c 100644 --- a/modules/vs/test/visual-feature/testFeatureSegment.cpp +++ b/modules/vs/test/visual-feature/testFeatureSegment.cpp @@ -79,10 +79,10 @@ int main(int argc, const char **argv) #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) {"-d", vpParseArgv::ARGV_CONSTANT_INT, 0, (char *)&opt_no_display, "Disable display and graphics viewer."}, #endif - {"-normalized", vpParseArgv::ARGV_INT, (char *)NULL, (char *)&opt_normalized, + {"-normalized", vpParseArgv::ARGV_INT, (char *)nullptr, (char *)&opt_normalized, "1 to use normalized features, 0 for non normalized."}, - {"-h", vpParseArgv::ARGV_HELP, (char *)NULL, (char *)NULL, "Print the help."}, - {(char *)NULL, vpParseArgv::ARGV_END, (char *)NULL, (char *)NULL, (char *)NULL} + {"-h", vpParseArgv::ARGV_HELP, (char *)nullptr, (char *)nullptr, "Print the help."}, + {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr} }; // Read the command line options @@ -103,7 +103,7 @@ int main(int argc, const char **argv) vpCameraParameters cam(640., 480., 320., 240.); #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) - vpDisplay *display = NULL; + vpDisplay *display = nullptr; if (!opt_no_display) { #if defined(VISP_HAVE_X11) display = new vpDisplayX; @@ -178,7 +178,7 @@ int main(int argc, const char **argv) #endif #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) - vpPlot *graph = NULL; + vpPlot *graph = nullptr; if (opt_curves) { // Create a window (700 by 700) at position (100, 200) with two graphics graph = new vpPlot(2, 500, 500, 700, 10, "Curves..."); @@ -239,11 +239,11 @@ int main(int argc, const char **argv) } while ((task.getError()).sumSquare() > 0.0005); #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) - if (graph != NULL) + if (graph != nullptr) delete graph; #endif #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) - if (!opt_no_display && display != NULL) + if (!opt_no_display && display != nullptr) delete display; #endif diff --git a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp index e7e088ad36..c0165739a7 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp @@ -45,9 +45,9 @@ int main(int argc, char **argv) g.open(config); if (opt_camera_index == 1) // Left camera - g.acquire(&I, NULL, NULL); + g.acquire(&I, nullptr, nullptr); else - g.acquire(NULL, &I, NULL); + g.acquire(nullptr, &I, nullptr); std::cout << "Read camera parameters from Realsense device" << std::endl; // Parameters of our camera @@ -86,9 +86,9 @@ int main(int argc, char **argv) double t_begin = vpTime::measureTimeMs(); if (opt_camera_index == 1) - g.acquire(&I, NULL, NULL); + g.acquire(&I, nullptr, nullptr); else - g.acquire(NULL, &I, NULL); + g.acquire(nullptr, &I, nullptr); vpDisplay::display(I); if (apply_cv) { diff --git a/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp b/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp index a4fea0a893..34f788d806 100644 --- a/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp +++ b/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp @@ -67,7 +67,7 @@ int main(int argc, const char **argv) #endif vpDisplay::setTitle(I, "ViSP viewer"); - vpDetectorBase *detector = NULL; + vpDetectorBase *detector = nullptr; #if (defined(VISP_HAVE_ZBAR) && defined(VISP_HAVE_DMTX)) if (opt_barcode == 0) detector = new vpDetectorQRCode; diff --git a/tutorial/detection/barcode/tutorial-barcode-detector.cpp b/tutorial/detection/barcode/tutorial-barcode-detector.cpp index ed75fa2f53..f00d6c0216 100644 --- a/tutorial/detection/barcode/tutorial-barcode-detector.cpp +++ b/tutorial/detection/barcode/tutorial-barcode-detector.cpp @@ -27,7 +27,7 @@ int main(int argc, const char **argv) #endif //! [Create base detector] - vpDetectorBase *detector = NULL; + vpDetectorBase *detector = nullptr; //! [Create base detector] #if (defined(VISP_HAVE_ZBAR) && defined(VISP_HAVE_DMTX)) diff --git a/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp b/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp index 3d2ae7e1b2..945935689f 100644 --- a/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp +++ b/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp @@ -193,7 +193,7 @@ bool parseOnnxModel(const std::string &model_path, TRTUniquePtr infer { nvinfer1::createInferRuntime(gLogger) }; - engine.reset(infer->deserializeCudaEngine(engineStream, engineSize, NULL)); + engine.reset(infer->deserializeCudaEngine(engineStream, engineSize, nullptr)); context.reset(engine->createExecutionContext()); return true; @@ -281,7 +281,7 @@ bool parseOnnxModel(const std::string &model_path, TRTUniquePtr I_undist(height, width); g.open(config); - g.acquire(&I_left, NULL, NULL); + g.acquire(&I_left, nullptr, nullptr); std::cout << "Read camera parameters from Realsense device" << std::endl; vpCameraParameters cam_left, cam_undistort; @@ -111,8 +111,8 @@ int main(int argc, const char **argv) std::cout << "nThreads : " << nThreads << std::endl; std::cout << "Z aligned: " << align_frame << std::endl; - vpDisplay *display_left = NULL; - vpDisplay *display_undistort = NULL; + vpDisplay *display_left = nullptr; + vpDisplay *display_undistort = nullptr; if (!display_off) { #ifdef VISP_HAVE_X11 display_left = new vpDisplayX(I_left, 100, 30, "Left image"); @@ -150,7 +150,7 @@ int main(int argc, const char **argv) double t = vpTime::measureTimeMs(); //! [Acquisition] - g.acquire(&I_left, NULL, NULL); + g.acquire(&I_left, nullptr, nullptr); //! [Undistorting image] vpImageTools::undistort(I_left, mapU, mapV, mapDu, mapDv, I_undist); diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp index 4331e930c3..d721296063 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp @@ -99,7 +99,7 @@ int main(int argc, const char **argv) rs2::align align_to_color = RS2_STREAM_COLOR; g.acquire(reinterpret_cast(I_color.bitmap), reinterpret_cast(I_depth_raw.bitmap), - NULL, NULL, &align_to_color); + nullptr, nullptr, &align_to_color); std::cout << "Read camera parameters from Realsense device" << std::endl; vpCameraParameters cam; @@ -116,9 +116,9 @@ int main(int argc, const char **argv) vpImage depthMap; vpImageConvert::createDepthHistogram(I_depth_raw, I_depth); - vpDisplay *d1 = NULL; - vpDisplay *d2 = NULL; - vpDisplay *d3 = NULL; + vpDisplay *d1 = nullptr; + vpDisplay *d2 = nullptr; + vpDisplay *d3 = nullptr; if (!display_off) { #ifdef VISP_HAVE_X11 d1 = new vpDisplayX(I_color, 100, 30, "Pose from Homography"); @@ -152,7 +152,7 @@ int main(int argc, const char **argv) //! [Acquisition] g.acquire(reinterpret_cast(I_color.bitmap), - reinterpret_cast(I_depth_raw.bitmap), NULL, NULL, &align_to_color); + reinterpret_cast(I_depth_raw.bitmap), nullptr, nullptr, &align_to_color); //! [Acquisition] I_color2 = I_color; diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp index 91002963ca..54a4c158db 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp @@ -114,9 +114,9 @@ int main(int argc, const char **argv) vpImage depthMap; vpImageConvert::createDepthHistogram(I_depth_raw, I_depth); - vpDisplay *d1 = NULL; - vpDisplay *d2 = NULL; - vpDisplay *d3 = NULL; + vpDisplay *d1 = nullptr; + vpDisplay *d2 = nullptr; + vpDisplay *d3 = nullptr; if (!display_off) { #ifdef VISP_HAVE_X11 d1 = new vpDisplayX(I_color, 100, 30, "Pose from Homography"); diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp index 1aeb9c2c59..f855805155 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp @@ -183,7 +183,7 @@ int main(int argc, const char **argv) std::cout << "nThreads : " << nThreads << std::endl; std::cout << "Z aligned: " << align_frame << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (!display_off) { #ifdef VISP_HAVE_X11 d = new vpDisplayX(I); diff --git a/tutorial/grabber/tutorial-grabber-1394.cpp b/tutorial/grabber/tutorial-grabber-1394.cpp index fe7bfddf5c..8b5794cf30 100644 --- a/tutorial/grabber/tutorial-grabber-1394.cpp +++ b/tutorial/grabber/tutorial-grabber-1394.cpp @@ -130,7 +130,7 @@ int main(int argc, const char *argv[]) std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp index d663548c24..4b267054ba 100644 --- a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp +++ b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp @@ -151,7 +151,7 @@ int main(int argc, const char *argv[]) std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/grabber/tutorial-grabber-bebop2.cpp b/tutorial/grabber/tutorial-grabber-bebop2.cpp index 7d5af10bd6..f88bd769c3 100644 --- a/tutorial/grabber/tutorial-grabber-bebop2.cpp +++ b/tutorial/grabber/tutorial-grabber-bebop2.cpp @@ -144,7 +144,7 @@ int main(int argc, const char **argv) std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/grabber/tutorial-grabber-flycapture.cpp b/tutorial/grabber/tutorial-grabber-flycapture.cpp index d9b65ea13d..fcf4b75c12 100644 --- a/tutorial/grabber/tutorial-grabber-flycapture.cpp +++ b/tutorial/grabber/tutorial-grabber-flycapture.cpp @@ -132,7 +132,7 @@ int main(int argc, const char *argv[]) std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp index 7c12ec12c2..b52ba492ce 100644 --- a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp +++ b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp @@ -297,7 +297,7 @@ int main(int argc, const char *argv[]) std::cout << "Config file : " << (opt_config_file.empty() ? "empty" : opt_config_file) << std::endl; std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp index 7df532fc8f..7f7fd8bcd3 100644 --- a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp @@ -83,7 +83,7 @@ int main(int argc, char **argv) for (size_t i = 0; i < type_serial_nb.size(); i++) { if (cam_found[i]) { if (type_serial_nb[i].first == "T265") { // T265. - g[i].acquire(&I[i], NULL, NULL); + g[i].acquire(&I[i], nullptr, nullptr); #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV) if (!d[i].isInitialised()) { diff --git a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp index 1c378ea21c..b42cc9f944 100644 --- a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp @@ -73,9 +73,9 @@ vpThread::Return displayFunction(vpThread::Args args) t_CaptureState capture_state_; bool display_initialized_ = false; #if defined(VISP_HAVE_X11) - vpDisplayX *d_ = NULL; + vpDisplayX *d_ = nullptr; #elif defined(VISP_HAVE_GDI) - vpDisplayGDI *d_ = NULL; + vpDisplayGDI *d_ = nullptr; #endif do { diff --git a/tutorial/grabber/tutorial-grabber-opencv.cpp b/tutorial/grabber/tutorial-grabber-opencv.cpp index 7978d6e770..5113934a3b 100644 --- a/tutorial/grabber/tutorial-grabber-opencv.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv.cpp @@ -139,7 +139,7 @@ int main(int argc, const char *argv[]) #endif vpImageConvert::convert(frame, I); - vpDisplayOpenCV *d = NULL; + vpDisplayOpenCV *d = nullptr; if (opt_display) { d = new vpDisplayOpenCV(I); } diff --git a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp index a592372027..193075629d 100644 --- a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp @@ -111,7 +111,7 @@ int main(int argc, const char *argv[]) std::cout << "Image size : " << I_left.getWidth() << " " << I_right.getHeight() << std::endl; - vpDisplay *display_left = NULL, *display_right = NULL; + vpDisplay *display_left = nullptr, *display_right = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; @@ -148,7 +148,7 @@ int main(int argc, const char *argv[]) vpDisplay::display(I_right); quit = image_queue_left.record(I_left); - quit |= image_queue_right.record(I_right, NULL, image_queue_left.getRecordingTrigger(), true); + quit |= image_queue_right.record(I_right, nullptr, image_queue_left.getRecordingTrigger(), true); std::stringstream ss; ss << "Acquisition time: " << std::setprecision(3) << vpTime::measureTimeMs() - t << " ms"; diff --git a/tutorial/grabber/tutorial-grabber-realsense.cpp b/tutorial/grabber/tutorial-grabber-realsense.cpp index 6c39b2a632..a4644a250b 100644 --- a/tutorial/grabber/tutorial-grabber-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense.cpp @@ -157,7 +157,7 @@ int main(int argc, const char *argv[]) std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp index 0108f2002a..971a599138 100644 --- a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp +++ b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp @@ -47,7 +47,7 @@ int main(int argc, char **argv) // Acquiring images. for (;;) { rs.acquire(reinterpret_cast(I_color_rs.bitmap), - reinterpret_cast(rs_I_depth_raw.bitmap), NULL, NULL, NULL, NULL, NULL); + reinterpret_cast(rs_I_depth_raw.bitmap), nullptr, nullptr, nullptr, nullptr, nullptr); sc.acquire(reinterpret_cast(I_color_sc.bitmap), reinterpret_cast(sc_I_depth_raw.bitmap)); diff --git a/tutorial/grabber/tutorial-grabber-structure-core.cpp b/tutorial/grabber/tutorial-grabber-structure-core.cpp index b668684ce8..2bfd2ecd0b 100644 --- a/tutorial/grabber/tutorial-grabber-structure-core.cpp +++ b/tutorial/grabber/tutorial-grabber-structure-core.cpp @@ -158,7 +158,7 @@ int main(int argc, const char *argv[]) I_depth = vpImage(g.getHeight(vpOccipitalStructure::depth), g.getWidth(vpOccipitalStructure::depth)); I_depth_raw = vpImage(g.getHeight(vpOccipitalStructure::depth), g.getWidth(vpOccipitalStructure::depth)); - vpDisplay *display_visible = NULL, *display_depth = NULL; + vpDisplay *display_visible = nullptr, *display_depth = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; @@ -200,7 +200,7 @@ int main(int argc, const char *argv[]) vpDisplay::display(I_depth); quit = image_queue_visible.record(I_color); - quit |= image_queue_depth.record(I_depth, NULL, image_queue_visible.getRecordingTrigger(), true); + quit |= image_queue_depth.record(I_depth, nullptr, image_queue_visible.getRecordingTrigger(), true); std::stringstream ss; ss << "Acquisition time: " << std::setprecision(3) << vpTime::measureTimeMs() - t << " ms"; diff --git a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp index 07880bbfb1..5a0c538a0a 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp @@ -61,7 +61,7 @@ vpThread::Return displayFunction(vpThread::Args args) t_CaptureState capture_state_; bool display_initialized_ = false; #if defined(VISP_HAVE_X11) - vpDisplayX *d_ = NULL; + vpDisplayX *d_ = nullptr; #endif do { diff --git a/tutorial/grabber/tutorial-grabber-v4l2.cpp b/tutorial/grabber/tutorial-grabber-v4l2.cpp index 245f04a2fb..64ecb33ad2 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2.cpp @@ -145,7 +145,7 @@ int main(int argc, const char *argv[]) std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl; - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (opt_display) { #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV)) std::cout << "No image viewer is available..." << std::endl; diff --git a/tutorial/ios/AprilTagLiveCamera/AprilTagLiveCamera.xcodeproj/project.pbxproj b/tutorial/ios/AprilTagLiveCamera/AprilTagLiveCamera.xcodeproj/project.pbxproj index 2b35534f7a..4b1d52b41a 100644 --- a/tutorial/ios/AprilTagLiveCamera/AprilTagLiveCamera.xcodeproj/project.pbxproj +++ b/tutorial/ios/AprilTagLiveCamera/AprilTagLiveCamera.xcodeproj/project.pbxproj @@ -223,7 +223,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_ANALYZER_NUMBER_OBJECT_CONVERSION = YES_AGGRESSIVE; CLANG_CXX_LANGUAGE_STANDARD = "gnu++14"; CLANG_CXX_LIBRARY = "libc++"; @@ -241,7 +241,7 @@ CLANG_WARN_ENUM_CONVERSION = YES; CLANG_WARN_INFINITE_RECURSION = YES; CLANG_WARN_INT_CONVERSION = YES; - CLANG_WARN_NON_LITERAL_NULL_CONVERSION = YES; + CLANG_WARN_NON_LITERAL_nullptr_CONVERSION = YES; CLANG_WARN_OBJC_IMPLICIT_RETAIN_SELF = YES; CLANG_WARN_OBJC_LITERAL_CONVERSION = YES; CLANG_WARN_OBJC_ROOT_CLASS = YES_ERROR; @@ -284,7 +284,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_ANALYZER_NUMBER_OBJECT_CONVERSION = YES_AGGRESSIVE; CLANG_CXX_LANGUAGE_STANDARD = "gnu++14"; CLANG_CXX_LIBRARY = "libc++"; @@ -302,7 +302,7 @@ CLANG_WARN_ENUM_CONVERSION = YES; CLANG_WARN_INFINITE_RECURSION = YES; CLANG_WARN_INT_CONVERSION = YES; - CLANG_WARN_NON_LITERAL_NULL_CONVERSION = YES; + CLANG_WARN_NON_LITERAL_nullptr_CONVERSION = YES; CLANG_WARN_OBJC_IMPLICIT_RETAIN_SELF = YES; CLANG_WARN_OBJC_LITERAL_CONVERSION = YES; CLANG_WARN_OBJC_ROOT_CLASS = YES_ERROR; diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm index 6075d1baca..3eab39980f 100755 --- a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm +++ b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm @@ -156,7 +156,7 @@ + (UIImage *)UIImageFromVpImageColor:(const vpImage &)I colorSpace, // colorspace kCGImageAlphaNone|kCGBitmapByteOrderDefault,// bitmap info provider, // CGDataProviderRef - NULL, // decode + nullptr, // decode false, // should interpolate kCGRenderingIntentDefault // intent ); @@ -192,7 +192,7 @@ + (UIImage *)UIImageFromVpImageGray:(const vpImage &)I colorSpace, // colorspace kCGImageAlphaNone|kCGBitmapByteOrderDefault,// bitmap info provider, // CGDataProviderRef - NULL, // decode + nullptr, // decode false, // should interpolate kCGRenderingIntentDefault // intent ); @@ -211,4 +211,3 @@ + (UIImage *)UIImageFromVpImageGray:(const vpImage &)I @end #endif - diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplayWithContext.h b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplayWithContext.h index 34fd2eafcd..1b41a85db4 100644 --- a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplayWithContext.h +++ b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplayWithContext.h @@ -37,7 +37,7 @@ #import "ImageDisplay.h" -NS_ASSUME_NONNULL_BEGIN +NS_ASSUME_NONnullptr_BEGIN @interface ImageDisplay (withContext) @@ -49,4 +49,4 @@ NS_ASSUME_NONNULL_BEGIN @end -NS_ASSUME_NONNULL_END +NS_ASSUME_NONnullptr_END diff --git a/tutorial/ios/GettingStarted/GettingStarted.xcodeproj/project.pbxproj b/tutorial/ios/GettingStarted/GettingStarted.xcodeproj/project.pbxproj index 6bcf630100..4f223c7077 100644 --- a/tutorial/ios/GettingStarted/GettingStarted.xcodeproj/project.pbxproj +++ b/tutorial/ios/GettingStarted/GettingStarted.xcodeproj/project.pbxproj @@ -182,7 +182,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_ANALYZER_NUMBER_OBJECT_CONVERSION = YES_AGGRESSIVE; CLANG_CXX_LANGUAGE_STANDARD = "gnu++0x"; CLANG_CXX_LIBRARY = "libc++"; @@ -231,7 +231,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_ANALYZER_NUMBER_OBJECT_CONVERSION = YES_AGGRESSIVE; CLANG_CXX_LANGUAGE_STANDARD = "gnu++0x"; CLANG_CXX_LIBRARY = "libc++"; diff --git a/tutorial/ios/StartedAprilTag/StartedAprilTag.xcodeproj/project.pbxproj b/tutorial/ios/StartedAprilTag/StartedAprilTag.xcodeproj/project.pbxproj index c46dc4a9e7..4576317c9d 100644 --- a/tutorial/ios/StartedAprilTag/StartedAprilTag.xcodeproj/project.pbxproj +++ b/tutorial/ios/StartedAprilTag/StartedAprilTag.xcodeproj/project.pbxproj @@ -198,7 +198,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_ANALYZER_NUMBER_OBJECT_CONVERSION = YES_AGGRESSIVE; CLANG_CXX_LANGUAGE_STANDARD = "gnu++0x"; CLANG_CXX_LIBRARY = "libc++"; @@ -247,7 +247,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_ANALYZER_NUMBER_OBJECT_CONVERSION = YES_AGGRESSIVE; CLANG_CXX_LANGUAGE_STANDARD = "gnu++0x"; CLANG_CXX_LIBRARY = "libc++"; diff --git a/tutorial/ios/StartedAprilTag/StartedAprilTag/ImageConversion.mm b/tutorial/ios/StartedAprilTag/StartedAprilTag/ImageConversion.mm index 5666d8d6ec..156710a531 100644 --- a/tutorial/ios/StartedAprilTag/StartedAprilTag/ImageConversion.mm +++ b/tutorial/ios/StartedAprilTag/StartedAprilTag/ImageConversion.mm @@ -156,7 +156,7 @@ + (UIImage *)UIImageFromVpImageColor:(const vpImage &)I colorSpace, // colorspace kCGImageAlphaNone|kCGBitmapByteOrderDefault,// bitmap info provider, // CGDataProviderRef - NULL, // decode + nullptr, // decode false, // should interpolate kCGRenderingIntentDefault // intent ); @@ -192,7 +192,7 @@ + (UIImage *)UIImageFromVpImageGray:(const vpImage &)I colorSpace, // colorspace kCGImageAlphaNone|kCGBitmapByteOrderDefault,// bitmap info provider, // CGDataProviderRef - NULL, // decode + nullptr, // decode false, // should interpolate kCGRenderingIntentDefault // intent ); @@ -211,4 +211,3 @@ + (UIImage *)UIImageFromVpImageGray:(const vpImage &)I @end #endif - diff --git a/tutorial/ios/StartedImageProc/StartedImageProc.xcodeproj/project.pbxproj b/tutorial/ios/StartedImageProc/StartedImageProc.xcodeproj/project.pbxproj index f6e5edad88..a8bbd2bc00 100644 --- a/tutorial/ios/StartedImageProc/StartedImageProc.xcodeproj/project.pbxproj +++ b/tutorial/ios/StartedImageProc/StartedImageProc.xcodeproj/project.pbxproj @@ -192,7 +192,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_CXX_LANGUAGE_STANDARD = "gnu++0x"; CLANG_CXX_LIBRARY = "libc++"; CLANG_ENABLE_MODULES = YES; @@ -240,7 +240,7 @@ isa = XCBuildConfiguration; buildSettings = { ALWAYS_SEARCH_USER_PATHS = NO; - CLANG_ANALYZER_NONNULL = YES; + CLANG_ANALYZER_NONnullptr = YES; CLANG_CXX_LANGUAGE_STANDARD = "gnu++0x"; CLANG_CXX_LIBRARY = "libc++"; CLANG_ENABLE_MODULES = YES; diff --git a/tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm b/tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm index 5666d8d6ec..156710a531 100644 --- a/tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm +++ b/tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm @@ -156,7 +156,7 @@ + (UIImage *)UIImageFromVpImageColor:(const vpImage &)I colorSpace, // colorspace kCGImageAlphaNone|kCGBitmapByteOrderDefault,// bitmap info provider, // CGDataProviderRef - NULL, // decode + nullptr, // decode false, // should interpolate kCGRenderingIntentDefault // intent ); @@ -192,7 +192,7 @@ + (UIImage *)UIImageFromVpImageGray:(const vpImage &)I colorSpace, // colorspace kCGImageAlphaNone|kCGBitmapByteOrderDefault,// bitmap info provider, // CGDataProviderRef - NULL, // decode + nullptr, // decode false, // should interpolate kCGRenderingIntentDefault // intent ); @@ -211,4 +211,3 @@ + (UIImage *)UIImageFromVpImageGray:(const vpImage &)I @end #endif - diff --git a/tutorial/matlab/tutorial-matlab.cpp b/tutorial/matlab/tutorial-matlab.cpp index f365026e6e..5bc97c1785 100644 --- a/tutorial/matlab/tutorial-matlab.cpp +++ b/tutorial/matlab/tutorial-matlab.cpp @@ -38,7 +38,7 @@ int main() mxArray *T = mxCreateDoubleMatrix(xRows, xCols, mxREAL); // MATLAB array to store output data from MATLAB - mxArray *D = NULL; + mxArray *D = nullptr; //! [MATLABVariables] // Temporary variable to hold Output data diff --git a/tutorial/robot/mbot/arduino/mbot-serial-controller/mbot-serial-controller.ino b/tutorial/robot/mbot/arduino/mbot-serial-controller/mbot-serial-controller.ino index 093fdcd6dd..4e1ed09875 100644 --- a/tutorial/robot/mbot/arduino/mbot-serial-controller/mbot-serial-controller.ino +++ b/tutorial/robot/mbot/arduino/mbot-serial-controller/mbot-serial-controller.ino @@ -13,7 +13,7 @@ MeEncoderOnBoard Encoder_1(SLOT1); MeEncoderOnBoard Encoder_2(SLOT2); // Me Auriga hardware serial port to dial with Raspberry -MeSerial mySerial(PORT_5); +MeSerial mySerial(PORT_5); // LED ring MeRGBLed rgbled(0, 12); @@ -85,7 +85,7 @@ String getValue(String string, String key, String separator) char * tmp; char * str; str = strtok_r((char*)string.c_str(), separator.c_str(), &tmp); - if(str!=NULL && strcmp(str,key.c_str())==0) { + if(str!=nullptr && strcmp(str,key.c_str())==0) { val = String(tmp); } } @@ -95,15 +95,15 @@ String getValue(String string, String key, String separator) void setup() { // Serial connexion with Raspberry mySerial.begin(115200); // Opens serial port at 115200 bps - + // Serial connexion with console used for debug info Serial.begin(115200); // Opens serial port at 9600 bps - + // Led ring rgbled.setpin(44); rgbled.setColor(0, 0, 0, 0); // Turn all LED off rgbled.show(); - + // Motors - Set Pwm 8KHz TCCR1A = _BV(WGM10); TCCR1B = _BV(CS11) | _BV(WGM12); @@ -183,7 +183,7 @@ void loop() { } } rgb[3] = atoi(string_rgb.c_str()); - + rgbled.setColor(rgb[0], rgb[1], rgb[2], rgb[3]); rgbled.show(); } @@ -201,6 +201,6 @@ void loop() { else { rgbled.setColor(6, 0, 1, 0); // Left LED turn GREEN rgbled.setColor(12, 0, 1, 0); // Right LED turn GREEN - rgbled.show(); + rgbled.show(); } -} +} 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 6c81ee38ba..03884fcf4c 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 @@ -79,7 +79,7 @@ int main(int argc, const char **argv) // if motor left: led 3 blue // if motor right: led 4 blue - vpSerial *serial = NULL; + vpSerial *serial = nullptr; if (!serial_off) { serial = new vpSerial("/dev/ttyAMA0", 115200); @@ -97,7 +97,7 @@ int main(int argc, const char **argv) g.setScale(1); g.acquire(I); - vpDisplay *d = NULL; + vpDisplay *d = nullptr; vpImage O; #ifdef VISP_HAVE_X11 if (display_on) { diff --git a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-ibvs.cpp b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-ibvs.cpp index 94ac5f992d..9a5ce986db 100644 --- a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-ibvs.cpp +++ b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-ibvs.cpp @@ -83,7 +83,7 @@ int main(int argc, const char **argv) // if motor left: led 3 blue // if motor right: led 4 blue - vpSerial *serial = NULL; + vpSerial *serial = nullptr; if (!serial_off) { serial = new vpSerial("/dev/ttyAMA0", 115200); @@ -101,7 +101,7 @@ int main(int argc, const char **argv) g.setScale(1); g.acquire(I); - vpDisplay *d = NULL; + vpDisplay *d = nullptr; vpImage O; #ifdef VISP_HAVE_X11 if (display_on) { diff --git a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp index e32164a65f..d9726cf305 100644 --- a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp +++ b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp @@ -73,7 +73,7 @@ int main(int argc, const char **argv) // if motor left: led 3 blue // if motor right: led 4 blue - vpSerial *serial = NULL; + vpSerial *serial = nullptr; if (!serial_off) { serial = new vpSerial("/dev/ttyAMA0", 115200); @@ -91,7 +91,7 @@ int main(int argc, const char **argv) g.setScale(1); g.acquire(I); - vpDisplay *d = NULL; + vpDisplay *d = nullptr; vpImage O; #ifdef VISP_HAVE_X11 if (display_on) { diff --git a/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-rs2.cpp b/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-rs2.cpp index 08a514324d..0a15fd9487 100644 --- a/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-rs2.cpp +++ b/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-rs2.cpp @@ -277,8 +277,8 @@ int main(int argc, const char **argv) std::cout << " Projection error: " << opt_projection_error_threshold << std::endl; // Construct display - vpDisplay *d_gray = NULL; - vpDisplay *d_depth = NULL; + vpDisplay *d_gray = nullptr; + vpDisplay *d_depth = nullptr; if (!display_off) { #ifdef VISP_HAVE_X11 @@ -370,10 +370,10 @@ int main(int argc, const char **argv) while (state != state_quit) { if (opt_use_depth) { #ifdef VISP_HAVE_PCL - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, pointcloud, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, pointcloud, nullptr); #else - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, NULL, - NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, nullptr, + nullptr); #endif vpImageConvert::convert(I_color, I_gray); vpImageConvert::createDepthHistogram(I_depth_raw, I_depth); diff --git a/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-webcam.cpp b/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-webcam.cpp index db19ce6318..4f25ea7001 100644 --- a/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-webcam.cpp +++ b/tutorial/tracking/model-based/generic-apriltag/tutorial-mb-generic-tracker-apriltag-webcam.cpp @@ -244,7 +244,7 @@ int main(int argc, const char **argv) std::cout << " Projection error: " << opt_projection_error_threshold << std::endl; // Construct display - vpDisplay *d = NULL; + vpDisplay *d = nullptr; if (!display_off) { #ifdef VISP_HAVE_X11 d = new vpDisplayX(I); diff --git a/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense-json-settings.cpp b/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense-json-settings.cpp index 9813864be5..bf3ad1c696 100644 --- a/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense-json-settings.cpp +++ b/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense-json-settings.cpp @@ -182,7 +182,7 @@ int main(int argc, char *argv []) d2.init(I_depth, _posx + I_gray.getWidth() + 10, _posy, "Depth stream"); while (true) { - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, nullptr); if (use_color) { vpImageConvert::convert(I_color, I_gray); @@ -223,7 +223,7 @@ int main(int argc, char *argv []) bool tracking_failed = false; // Acquire images and update tracker input data - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, NULL, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, nullptr, nullptr); if (use_color) { vpImageConvert::convert(I_color, I_gray); diff --git a/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense.cpp b/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense.cpp index ea6eb1db86..d9997ada0c 100644 --- a/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense.cpp +++ b/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-realsense.cpp @@ -181,7 +181,7 @@ int main(int argc, char *argv[]) d2.init(I_depth, _posx + I_gray.getWidth() + 10, _posy, "Depth stream"); while (true) { - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, nullptr); if (use_edges || use_klt) { vpImageConvert::convert(I_color, I_gray); @@ -319,7 +319,7 @@ int main(int argc, char *argv[]) bool tracking_failed = false; // Acquire images and update tracker input data - realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, NULL, NULL); + realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, nullptr, nullptr); if (use_edges || use_klt || run_auto_init) { vpImageConvert::convert(I_color, I_gray); diff --git a/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-structure-core.cpp b/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-structure-core.cpp index 0888b859ec..623f510f33 100644 --- a/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-structure-core.cpp +++ b/tutorial/tracking/model-based/generic-rgbd/tutorial-mb-generic-tracker-rgbd-structure-core.cpp @@ -178,7 +178,7 @@ int main(int argc, char *argv[]) d2.init(I_depth, _posx + I_gray.getWidth() + 10, _posy, "Depth stream"); while (true) { - sc.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, NULL, NULL, NULL); + sc.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, nullptr, nullptr); if (use_edges || use_klt) { vpImageConvert::convert(I_color, I_gray); diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp index a201e10225..02e666324a 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp @@ -26,9 +26,9 @@ int main(int argc, char **argv) unsigned int thickness = 2; vpImage I; - vpDisplay *display = NULL; - vpPlot *plot = NULL; - vpVideoWriter *writer = NULL; + vpDisplay *display = nullptr; + vpPlot *plot = nullptr; + vpVideoWriter *writer = nullptr; try { for (int i = 0; i < argc; i++) { diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-live.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-live.cpp index b8853ed417..5520d37ab7 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-live.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-live.cpp @@ -206,7 +206,7 @@ int main(int argc, char **argv) #endif //! [Grabber] - vpDisplay *display = NULL; + vpDisplay *display = nullptr; #if defined(VISP_HAVE_X11) display = new vpDisplayX; #elif defined(VISP_HAVE_GDI) diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker.cpp index c687d1d01e..1dcd1d4c35 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker.cpp @@ -54,7 +54,7 @@ int main(int argc, char **argv) g.setFileName(opt_videoname); g.open(I); - vpDisplay *display = NULL; + vpDisplay *display = nullptr; #if defined(VISP_HAVE_X11) display = new vpDisplayX; #elif defined(VISP_HAVE_GDI) diff --git a/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker-full.cpp b/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker-full.cpp index ad19b67f52..a0ec20dbea 100644 --- a/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker-full.cpp +++ b/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker-full.cpp @@ -58,7 +58,7 @@ int main(int argc, char **argv) g.setFileName(opt_videoname); g.open(I); - vpDisplay *display = NULL; + vpDisplay *display = nullptr; #if defined(VISP_HAVE_X11) display = new vpDisplayX; #elif defined(VISP_HAVE_GDI) diff --git a/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker.cpp b/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker.cpp index a164189975..18dcb8108e 100644 --- a/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker.cpp +++ b/tutorial/tracking/model-based/old/generic/tutorial-mb-tracker.cpp @@ -56,7 +56,7 @@ int main(int argc, char **argv) g.setFileName(opt_videoname); g.open(I); - vpDisplay *display = NULL; + vpDisplay *display = nullptr; #if defined(VISP_HAVE_X11) display = new vpDisplayX; #elif defined(VISP_HAVE_GDI)