Package org.robwork.sdurw_sensor
Class ImageUtil
- java.lang.Object
-
- org.robwork.sdurw_sensor.ImageUtil
-
public class ImageUtil extends java.lang.Objecta collection of simple image utility functions
-
-
Constructor Summary
Constructors Constructor Description ImageUtil(long cPtr, boolean cMemoryOwn)
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description voiddelete()static voidflipX(Image img)flips the image around the x-axis (horizontal)static voidflipY(Image img)flips the image around the y-axis (vertical)static longgetCPtr(ImageUtil obj)static ImagePtrmakeDepthImage(PointCloud cloud)Conditional comment:
End of conditional comment.
convert pointcloud to a depth image.static ImagePtrmakeDepthImage(PointCloud cloud, float min, float max)convert pointcloud to a depth image.static voidreset(Image img)sets the value of all channels of an image to
color.static voidreset(Image img, int color)sets the value of all channels of an image to
color.static voidRGB2GRAY(Image src, Image dst)converts an image of RGB type into an image of
GRAY type.
-
-
-
Method Detail
-
getCPtr
public static long getCPtr(ImageUtil obj)
-
delete
public void delete()
-
RGB2GRAY
public static void RGB2GRAY(Image src, Image dst)
converts an image of RGB type into an image of
GRAY type.
-
reset
public static void reset(Image img, int color)
sets the value of all channels of an image to
color.
-
reset
public static void reset(Image img)
sets the value of all channels of an image to
color.
-
flipX
public static void flipX(Image img)
flips the image around the x-axis (horizontal)- Parameters:
img-
-
flipY
public static void flipY(Image img)
flips the image around the y-axis (vertical)- Parameters:
img-
-
makeDepthImage
public static ImagePtr makeDepthImage(PointCloud cloud)
Conditional comment:
End of conditional comment.
convert pointcloud to a depth image. Colors are scaled to min and ax distance of
points.- Parameters:
cloud- [in] cloud to convert to image- Returns:
- image showing the pointcloud as a depth image
-
makeDepthImage
public static ImagePtr makeDepthImage(PointCloud cloud, float min, float max)
convert pointcloud to a depth image. Colors are scaled to min and max distance
specified by user- Parameters:
cloud- [in] cloud to convert to imagemin- [in] the minimum distance corresponding to blackmax- [in] the maximum distance corresponding to white- Returns:
- image showing the pointcloud as a depth image
-
-