Skip to content

Commit

Permalink
[nodes] Clean-up: Harmonize nodes' descriptions
Browse files Browse the repository at this point in the history
  • Loading branch information
cbentejac committed Oct 17, 2023
1 parent dc513e6 commit 086a239
Show file tree
Hide file tree
Showing 25 changed files with 173 additions and 173 deletions.
14 changes: 7 additions & 7 deletions meshroom/nodes/aliceVision/CameraInit.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
value=-1.0, uid=[0], range=None),
desc.FloatParam(name="focalLength", label="Focal Length", description="Known/calibrated focal length (in mm).", value=1000.0, uid=[0], range=(0.0, 10000.0, 1.0)),
desc.FloatParam(name="pixelRatio", label="Pixel Ratio", description="Ratio between the pixel width and the pixel height.", value=1.0, uid=[0], range=(0.0, 10.0, 0.1)),
desc.BoolParam(name='pixelRatioLocked', label='Pixel Ratio Locked',
description='The pixel ratio value is locked for estimation.',
desc.BoolParam(name="pixelRatioLocked", label="Pixel Ratio Locked",
description="The pixel ratio value is locked for estimation.",
value=True, uid=[0]),
desc.ChoiceParam(name="type", label="Camera Type",
description="Mathematical model used to represent a camera:\n"
Expand Down Expand Up @@ -241,7 +241,7 @@ class CameraInit(desc.AVCommandLineNode, desc.InitNode):
desc.ChoiceParam(
name="allowedCameraModels",
label="Allowed Camera Models",
description='List of the camera models that can be attributed.',
description="List of the camera models that can be attributed.",
value=["pinhole", "radial1", "radial3", "brown", "fisheye4", "fisheye1", "3deanamorphic4", "3deradial4", "3declassicld"],
values=["pinhole", "radial1", "radial3", "brown", "fisheye4", "fisheye1", "3deanamorphic4", "3deradial4", "3declassicld"],
exclusive=False,
Expand Down Expand Up @@ -320,10 +320,10 @@ class CameraInit(desc.AVCommandLineNode, desc.InitNode):

outputs = [
desc.File(
name='output',
label='SfMData',
description='''Output SfMData.''',
value=desc.Node.internalFolder + 'cameraInit.sfm',
name="output",
label="SfMData",
description="Output SfMData.",
value=desc.Node.internalFolder + "cameraInit.sfm",
uid=[],
),
]
Expand Down
2 changes: 1 addition & 1 deletion meshroom/nodes/aliceVision/CameraRigCalibration.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class CameraRigCalibration(desc.AVCommandLineNode):
inputs = [
desc.File(
name="sfmdata",
label='SfMData',
label="SfMData",
description="Input SfMData file.",
value="",
uid=[0],
Expand Down
46 changes: 23 additions & 23 deletions meshroom/nodes/aliceVision/CheckerboardDetection.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,51 +17,51 @@ class CheckerboardDetection(desc.AVCommandLineNode):

inputs = [
desc.File(
name='input',
label='Input',
description='SfMData File. Viewpoints must correspond to lens calibration grids.',
value='',
name="input",
label="Input",
description="Input SfMData file. Viewpoints must correspond to lens calibration grids.",
value="",
uid=[0],
),
desc.BoolParam(
name='useNestedGrids',
label='Nested calibration grid',
description='Images contain nested calibration grids. These grids must be centered on the image center.',
name="useNestedGrids",
label="Nested Calibration Grid",
description="Enable if images contain nested calibration grids. These grids must be centered on the image center.",
value=False,
uid=[0],
),
desc.BoolParam(
name='doubleSize',
label='Double Size',
description='Double the image size prior to processing',
name="doubleSize",
label="Double Size",
description="Double the image size prior to processing.",
value=False,
uid=[0],
),
desc.BoolParam(
name='exportDebugImages',
label='Export Debug Images',
description='Export Debug Images',
name="exportDebugImages",
label="Export Debug Images",
description="Export debug images.",
value=False,
uid=[0],
),
]

outputs = [
desc.File(
name='output',
label='Folder',
description='',
name="output",
label="Folder",
description="Output folder.",
value=desc.Node.internalFolder,
uid=[],
),
desc.File(
name='checkerLines',
enabled= lambda node: node.exportDebugImages.value,
label='Checker Lines',
description='Debug Images.',
semantic='image',
value=desc.Node.internalFolder + '<VIEW_ID>.png',
group='', # do not export on the command line
name="checkerLines",
enabled=lambda node: node.exportDebugImages.value,
label="Checker Lines",
description="Debug images.",
semantic="image",
value=desc.Node.internalFolder + "<VIEW_ID>.png",
group="", # do not export on the command line
uid=[],
),
]
4 changes: 2 additions & 2 deletions meshroom/nodes/aliceVision/ConvertMesh.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@ class ConvertMesh(desc.AVCommandLineNode):
),
desc.ChoiceParam(
name="outputMeshFileType",
label="File Type",
label="Output File Type",
description="Output mesh format (*.obj, *.gltf, *.fbx, *.stl).",
value="obj",
values=("gltf", "obj", "fbx", "stl"),
values=["gltf", "obj", "fbx", "stl"],
exclusive=True,
uid=[0],
group="",
Expand Down
4 changes: 2 additions & 2 deletions meshroom/nodes/aliceVision/ConvertSfMFormat.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ class ConvertSfMFormat(desc.AVCommandLineNode):
desc.File(
name="input",
label="Input",
description="SfMData file.",
description="Input SfMData file.",
value="",
uid=[0],
),
Expand Down Expand Up @@ -45,7 +45,7 @@ class ConvertSfMFormat(desc.AVCommandLineNode):
elementDesc=desc.File(
name="imageId",
label="Image ID",
description="UID or path of an image to add to the whitelist.",
description="UID or path of an image to add to the white list.",
value="",
uid=[0],
),
Expand Down
28 changes: 14 additions & 14 deletions meshroom/nodes/aliceVision/DepthMap.py
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ class DepthMap(desc.AVCommandLineNode):
value=1,
range=(-1, 10, 1),
uid=[0],
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.IntParam(
name="refineStepXY",
Expand All @@ -308,7 +308,7 @@ class DepthMap(desc.AVCommandLineNode):
value=1,
range=(-1, 10, 1),
uid=[0],
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.IntParam(
name="refineMaxTCamsPerTile",
Expand All @@ -317,7 +317,7 @@ class DepthMap(desc.AVCommandLineNode):
value=4,
range=(1, 20, 1),
uid=[0],
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.IntParam(
name="refineSubsampling",
Expand All @@ -327,7 +327,7 @@ class DepthMap(desc.AVCommandLineNode):
range=(1, 30, 1),
uid=[0],
advanced=True,
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.IntParam(
name="refineHalfNbDepths",
Expand All @@ -339,7 +339,7 @@ class DepthMap(desc.AVCommandLineNode):
range=(1, 50, 1),
uid=[0],
advanced=True,
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.IntParam(
name="refineWSH",
Expand All @@ -349,7 +349,7 @@ class DepthMap(desc.AVCommandLineNode):
range=(1, 20, 1),
uid=[0],
advanced=True,
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.FloatParam(
name="refineSigma",
Expand All @@ -359,7 +359,7 @@ class DepthMap(desc.AVCommandLineNode):
range=(0.0, 30.0, 0.5),
uid=[0],
advanced=True,
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.FloatParam(
name="refineGammaC",
Expand All @@ -369,7 +369,7 @@ class DepthMap(desc.AVCommandLineNode):
range=(0.0, 30.0, 0.5),
uid=[0],
advanced=True,
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.FloatParam(
name="refineGammaP",
Expand All @@ -379,23 +379,23 @@ class DepthMap(desc.AVCommandLineNode):
range=(0.0, 30.0, 0.5),
uid=[0],
advanced=True,
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.BoolParam(
name="refineInterpolateMiddleDepth",
label="Interpolate Middle Depth",
description="Enable middle depth bilinear interpolation.",
value=False,
uid=[0],
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
desc.BoolParam(
name="refineUseConsistentScale",
label="Consistent Scale",
description="Compare patch with consistent scale for similarity volume computation.",
value=False,
uid=[0],
enabled= lambda node: node.refine.refineEnabled.value,
enabled=lambda node: node.refine.refineEnabled.value,
),
]
),
Expand All @@ -420,7 +420,7 @@ class DepthMap(desc.AVCommandLineNode):
range=(1, 500, 10),
uid=[0],
advanced=True,
enabled= lambda node: node.colorOptimization.colorOptimizationEnabled.value,
enabled=lambda node: node.colorOptimization.colorOptimizationEnabled.value,
),
]
),
Expand Down Expand Up @@ -452,7 +452,7 @@ class DepthMap(desc.AVCommandLineNode):
label="Subparts",
description="User custom patch pattern subparts for similarity volume computation.",
advanced=True,
enabled= lambda node: (node.customPatchPattern.sgmUseCustomPatchPattern.value or node.customPatchPattern.refineUseCustomPatchPattern.value),
enabled=lambda node: (node.customPatchPattern.sgmUseCustomPatchPattern.value or node.customPatchPattern.refineUseCustomPatchPattern.value),
elementDesc=desc.GroupAttribute(
name="customPatchPatternSubpart",
label="Patch Pattern Subpart",
Expand Down Expand Up @@ -511,7 +511,7 @@ class DepthMap(desc.AVCommandLineNode):
value=False,
uid=[0],
advanced=True,
enabled= lambda node: (node.customPatchPattern.sgmUseCustomPatchPattern.value or node.customPatchPattern.refineUseCustomPatchPattern.value),
enabled=lambda node: (node.customPatchPattern.sgmUseCustomPatchPattern.value or node.customPatchPattern.refineUseCustomPatchPattern.value),
),
]
),
Expand Down
2 changes: 1 addition & 1 deletion meshroom/nodes/aliceVision/ExportAnimatedCamera.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class ExportAnimatedCamera(desc.AVCommandLineNode):
values=["jpg", "png", "tif", "exr"],
exclusive=True,
uid=[0],
enabled= lambda node: node.exportUndistortedImages.value,
enabled=lambda node: node.exportUndistortedImages.value,
),
desc.BoolParam(
name="exportFullROD",
Expand Down
38 changes: 19 additions & 19 deletions meshroom/nodes/aliceVision/ExportDistortion.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,38 +12,38 @@ class ExportDistortion(desc.AVCommandLineNode):

inputs = [
desc.File(
name='input',
label='Input SfMData',
description='SfMData file.',
value='',
name="input",
label="Input SfMData",
description="Input SfMData file.",
value="",
uid=[0],
),
]

outputs = [
desc.File(
name='output',
label='Folder',
description='Output folder.',
name="output",
label="Folder",
description="Output folder.",
value=desc.Node.internalFolder,
uid=[],
),
desc.File(
name='distoStMap',
label='Distortion ST Map',
description='Calibrated distortion ST map.',
semantic='image',
value=desc.Node.internalFolder + '<INTRINSIC_ID>_distort.exr',
group='', # do not export on the command line
name="distoStMap",
label="Distortion ST Map",
description="Calibrated distortion ST map.",
semantic="image",
value=desc.Node.internalFolder + "<INTRINSIC_ID>_distort.exr",
group="", # do not export on the command line
uid=[],
),
desc.File(
name='undistoStMap',
label='Undistortion ST Map',
description='Calibrated undistortion ST map.',
semantic='image',
value=desc.Node.internalFolder + '<INTRINSIC_ID>_undistort.exr',
group='', # do not export on the command line
name="undistoStMap",
label="Undistortion ST Map",
description="Calibrated undistortion ST map.",
semantic="image",
value=desc.Node.internalFolder + "<INTRINSIC_ID>_undistort.exr",
group="", # do not export on the command line
uid=[],
),
]
18 changes: 9 additions & 9 deletions meshroom/nodes/aliceVision/ImageProcessing.py
Original file line number Diff line number Diff line change
Expand Up @@ -406,7 +406,7 @@ class ImageProcessing(desc.AVCommandLineNode):
desc.BoolParam(
name="nlmFilterEnabled",
label="Enable",
description='Use Non-Local Mean Denoising from OpenCV to denoise images.',
description="Use Non-Local Mean Denoising from OpenCV to denoise images.",
value=False,
uid=[0],
),
Expand Down Expand Up @@ -580,17 +580,17 @@ class ImageProcessing(desc.AVCommandLineNode):
),

desc.File(
name='lensCorrectionProfileInfo',
label='Lens Correction Profile Info',
description='''Lens Correction Profile filepath or database directory.''',
value='${ALICEVISION_LENS_PROFILE_INFO}',
name="lensCorrectionProfileInfo",
label="Lens Correction Profile Info",
description="Lens Correction Profile filepath or database directory.",
value="${ALICEVISION_LENS_PROFILE_INFO}",
uid=[],
),

desc.BoolParam(
name='lensCorrectionProfileSearchIgnoreCameraModel',
label='LCP Generic Search',
description='The lens name and camera maker are used to match the LCP database, but the camera model is ignored.',
name="lensCorrectionProfileSearchIgnoreCameraModel",
label="LCP Generic Search",
description="The lens name and camera maker are used to match the LCP database, but the camera model is ignored.",
value=True,
uid=[0],
advanced=True,
Expand Down Expand Up @@ -682,7 +682,7 @@ class ImageProcessing(desc.AVCommandLineNode):
label="Images",
description="Output images.",
semantic="image",
value= outputImagesValueFunct,
value=outputImagesValueFunct,
group="", # do not export on the command line
uid=[],
),
Expand Down
Loading

0 comments on commit 086a239

Please sign in to comment.