Zivid C++ API  1.8.1+6967bc1b-1
Defining the Future of 3D Machine Vision
Zivid sample code

Examples of how to use the Zivid camera from C++

The examples on this page show how to get started using the Zivid Camera. All the code are also available as C++ source in the installation.

Capture using Zivid

The following examples assume you have a Zivid camera connected.

Capture 3D point cloud

This example captures a 3D point cloud using a Zivid camera, then writes the data to disk.

#include <Zivid/Zivid.h>
#include <chrono>
#include <iostream>
int main()
{
try
{
auto resultFile = "result.zdf";
std::cout << "Connecting to camera" << std::endl;
auto camera = zivid.connectCamera();
std::cout << "Adjusting the camera settings" << std::endl;
camera << Zivid::Settings::Iris{ 20 } << Zivid::Settings::ExposureTime{ std::chrono::microseconds{ 8333 } }
std::cout << "Capture a frame" << std::endl;
auto frame = camera.capture();
std::cout << "Saving frame to file: " << resultFile << std::endl;
frame.save(resultFile);
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Capture 3D point cloud and visualize it

This example captures a 3D point cloud using a Zivid camera, then displays it using the CloudVisualizer class included in the API.

#include <Zivid/Zivid.h>
#include <iostream>
int main()
{
try
{
std::cout << "Setting up visualization" << std::endl;
std::cout << "Connecting to camera" << std::endl;
auto camera = zivid.connectCamera();
std::cout << "Adjusting the iris" << std::endl;
camera << Zivid::Settings::Iris{ 20 };
std::cout << "Capture a frame" << std::endl;
auto frame = camera.capture();
std::cout << "Display the frame" << std::endl;
vis.show(frame);
vis.resetToFit();
std::cout << "Run the visualizer. Block until window closes" << std::endl;
vis.run();
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Capture HDR 3D point cloud

This example captures a HDR 3D point cloud by combining frames with several different iris values.

#include <Zivid/Zivid.h>
#include <iostream>
int main()
{
try
{
std::cout << "Setting up visualization" << std::endl;
std::cout << "Connecting to camera" << std::endl;
auto camera = zivid.connectCamera();
std::cout << "Recording HDR source images" << std::endl;
std::vector<Zivid::Frame> frames;
for(const size_t iris : { 20U, 25U, 30U })
{
std::cout << "Capture frame with iris = " << iris << std::endl;
camera << Zivid::Settings::Iris{ iris };
frames.emplace_back(camera.capture());
}
std::cout << "Creating HDR frame" << std::endl;
auto hdrFrame = Zivid::HDR::combineFrames(begin(frames), end(frames));
std::cout << "Saving the frames" << std::endl;
frames[0].save("20.zdf");
frames[1].save("25.zdf");
frames[2].save("30.zdf");
hdrFrame.save("HDR.zdf");
std::cout << "Display the frame" << std::endl;
vis.show(hdrFrame);
vis.resetToFit();
std::cout << "Run the visualizer. Block until window closes" << std::endl;
vis.run();
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Capture 2D image

This example captures a 2D image using the Zivid camera and saves the image to disk.

#include <Zivid/Zivid.h>
#include <chrono>
#include <iostream>
int main()
{
try
{
std::cout << "Connecting to camera" << std::endl;
auto camera = zivid.connectCamera();
std::cout << "Setting the capture settings" << std::endl;
auto settings = Zivid::Settings2D();
settings.set(Zivid::Settings2D::ExposureTime{ std::chrono::microseconds{ 10000 } });
settings.set(Zivid::Settings2D::Gain{ 1.0 });
settings.set(Zivid::Settings2D::Iris{ 35 });
std::cout << "Capture a 2D frame" << std::endl;
auto frame = camera.capture2D(settings);
std::cout << "Get RGBA8 image from Frame2D" << std::endl;
auto image = frame.image<Zivid::RGBA8>();
std::cout << "Get pixel color at row=100, column=50" << std::endl;
auto pixel = image(100, 50);
std::cout << "Pixel color: R=" << static_cast<int>(pixel.r) << ", G=" << static_cast<int>(pixel.g)
<< ", B=" << static_cast<int>(pixel.b) << ", A=" << static_cast<int>(pixel.a) << std::endl;
auto resultFile = "result.png";
std::cout << "Saving the image to " << resultFile << std::endl;
image.save(resultFile);
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Capture using Capture Assistant

This example shows how to use the Capture Assistant to find recommended capture settings for your scene, and then capture using those settings.

#include <Zivid/HDR.h>
#include <Zivid/Zivid.h>
#include <chrono>
#include <iostream>
int main()
{
try
{
std::cout << "Connecting to camera" << std::endl;
auto camera{ zivid.connectCamera() };
const auto resultFile{ "result.zdf" };
std::chrono::milliseconds{ 1200 }, Zivid::CaptureAssistant::AmbientLightFrequency::none);
std::cout << "Running Capture Assistant with parameters: " << suggestSettingsParameters << std::endl;
const auto settingsVector{ Zivid::CaptureAssistant::suggestSettings(camera, suggestSettingsParameters) };
std::cout << "Suggested settings are:" << std::endl;
for(const auto &setting : settingsVector)
{
std::cout << setting << std::endl;
}
std::cout << "Capture (and merge) frames using automatically suggested settings" << std::endl;
const auto hdrFrame{ Zivid::HDR::capture(camera, settingsVector) };
std::cout << "Saving frame to file: " << resultFile << std::endl;
hdrFrame.save(resultFile);
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Zivid capture from file

The following examples assume you do not use a Zivid camera, but have data files emulating its functionality.

Zivid capture from file - simple

This example captures a 3D point cloud from a virtual camera using data from file, then writes the data to disk.

// Please make sure that Zivid sample data has been selected during installation of Zivid software.
// Latest version of Zivid software (including samples) can be found at http://zivid.com/software/.
#include <Zivid/Zivid.h>
#include <iostream>
int main()
{
try
{
auto zdfFile = Zivid::Environment::dataPath() + "/MiscObjects.zdf";
auto resultFile = "result.zdf";
std::cout << "Initializing camera emulation using file: " << zdfFile << std::endl;
auto camera = zivid.createFileCamera(zdfFile);
std::cout << "Capture a frame" << std::endl;
auto frame = camera.capture();
std::cout << "Saving frame to file: " << resultFile << std::endl;
frame.save(resultFile);
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Zivid capture from file with visualization

This example captures a 3D point cloud from a virtual camera using data from file, then visualizes the data.

// Please make sure that Zivid sample data has been selected during installation of Zivid software.
// Latest version of Zivid software (including samples) can be found at http://zivid.com/software/.
#include <Zivid/Zivid.h>
#include <iostream>
int main()
{
try
{
std::cout << "Setting up visualization" << std::endl;
auto zdfFile = Zivid::Environment::dataPath() + "/MiscObjects.zdf";
std::cout << "Initializing camera emulation using file: " << zdfFile << std::endl;
auto camera = zivid.createFileCamera(zdfFile);
std::cout << "Capture a frame" << std::endl;
auto frame = camera.capture();
std::cout << "Display the frame" << std::endl;
vis.show(frame);
vis.resetToFit();
std::cout << "Run the visualizer. Block until window closes" << std::endl;
vis.run();
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}

Hand-eye calibration

This example shows how you can perform hand-eye-calibration using the Zivid API.

#include <iostream>
namespace
{
enum class CommandType
{
cmdAddPose,
cmdCalibrate,
cmdUnknown
};
std::string getInput()
{
std::string command;
std::getline(std::cin, command);
return command;
}
CommandType enterCommand()
{
std::cout << "Enter command, p (to add robot pose) or c (to perform calibration): ";
const auto command = getInput();
if(command == "P" || command == "p")
{
return CommandType::cmdAddPose;
}
if(command == "C" || command == "c")
{
return CommandType::cmdCalibrate;
}
return CommandType::cmdUnknown;
}
Zivid::HandEye::Pose enterRobotPose(size_t index)
{
std::cout << "Enter pose with id (a line with 16 space separated values describing 4x4 row-major matrix) : "
<< index << std::endl;
std::stringstream input(getInput());
double element{ 0 };
std::vector<double> transformElements;
for(size_t i = 0; i < 16 && input >> element; ++i)
{
transformElements.emplace_back(element);
}
const auto robotPose{ Zivid::Matrix4d{ transformElements.cbegin(), transformElements.cend() } };
std::cout << "The following pose was entered: \n" << robotPose << std::endl;
return robotPose;
}
Zivid::Frame acquireCheckerboardFrame(Zivid::Camera &camera)
{
std::cout << "Capturing checkerboard image... " << std::flush;
auto settings{ Zivid::Settings{} };
settings.set(Zivid::Settings::Iris{ 17 });
settings.set(Zivid::Settings::Gain{ 1.0 });
settings.set(Zivid::Settings::Brightness{ 1.0 });
settings.set(Zivid::Settings::ExposureTime{ std::chrono::microseconds{ 20000 } });
camera.setSettings(settings);
const auto frame = camera.capture();
std::cout << "OK" << std::endl;
return frame;
}
} // namespace
int main()
{
try
{
std::cout << "Connecting to camera..." << std::endl;
auto camera{ zivid.connectCamera() };
size_t currPoseId{ 0 };
bool calibrate{ false };
std::vector<Zivid::HandEye::CalibrationInput> input;
do
{
switch(enterCommand())
{
case CommandType::cmdAddPose:
{
try
{
const auto robotPose = enterRobotPose(currPoseId);
const auto frame = acquireCheckerboardFrame(camera);
std::cout << "Detecting checkerboard square centers... " << std::flush;
const auto result = Zivid::HandEye::detectFeaturePoints(frame.getPointCloud());
if(result)
{
std::cout << "OK" << std::endl;
input.emplace_back(Zivid::HandEye::CalibrationInput{ robotPose, result });
currPoseId++;
}
else
{
std::cout << "FAILED" << std::endl;
}
}
catch(const std::exception &e)
{
std::cout << "Error: " << Zivid::toString(e) << std::endl;
continue;
}
break;
}
case CommandType::cmdCalibrate:
{
calibrate = true;
break;
}
case CommandType::cmdUnknown:
{
std::cout << "Error: Unknown command" << std::endl;
break;
}
}
} while(!calibrate);
std::cout << "Performing hand-eye calibration ... " << std::flush;
const auto calibrationResult{ Zivid::HandEye::calibrateEyeToHand(input) };
if(calibrationResult)
{
std::cout << "OK\n"
<< "Result:\n"
<< calibrationResult << std::endl;
}
else
{
std::cerr << "\nFAILED" << std::endl;
return EXIT_FAILURE;
}
}
catch(const std::exception &e)
{
std::cerr << "\nError: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
return EXIT_SUCCESS;
}

User data

This example shows how to store custom user data on the camera.

#include <Zivid/Zivid.h>
#include <iostream>
namespace
{
enum class Mode
{
read,
write,
clear
};
std::invalid_argument usageException(const char *const *argv)
{
return std::invalid_argument{ std::string{ "Usage: " } + argv[0] + " <read|write <string>|clear>" };
}
Mode getMode(int argc, const char *const *argv)
{
if(argc >= 2)
{
if(std::string{ "read" } == argv[1])
{
return Mode::read;
}
if(std::string{ "write" } == argv[1])
{
return Mode::write;
}
if(std::string{ "clear" } == argv[1])
{
return Mode::clear;
}
}
throw usageException(argv);
}
std::string getWriteData(int argc, const char *const *argv)
{
if(argc >= 3)
{
return argv[2];
}
else
{
throw usageException(argv);
}
}
void write(Zivid::Camera &camera, const std::string &string)
{
camera.writeUserData(std::vector<uint8_t>{ begin(string), end(string) });
}
void clear(Zivid::Camera &camera)
{
write(camera, "");
}
std::string read(Zivid::Camera &camera)
{
const auto data = camera.userData();
return std::string{ begin(data), end(data) };
}
} // namespace
int main(int argc, char **argv)
{
try
{
std::cout << "Connecting to camera" << std::endl;
auto camera = zivid.connectCamera();
const auto maxDataSize = camera.userDataMaxSizeBytes();
if(maxDataSize == 0)
{
throw std::runtime_error{ "This camera does not support user data" };
}
switch(getMode(argc, argv))
{
case Mode::read:
std::cout << "Reading user data from camera" << std::endl;
std::cout << "Done. User data: '" << read(camera) << "'" << std::endl;
break;
case Mode::write:
{
auto userData = getWriteData(argc, argv);
std::cout << "Writing '" << userData << "' to the camera" << std::endl;
write(camera, userData);
std::cout << "Done" << std::endl;
break;
}
case Mode::clear:
std::cout << "Clearing user data from camera" << std::endl;
clear(camera);
std::cout << "Done" << std::endl;
break;
}
}
catch(const std::exception &e)
{
std::cerr << "Error: " << Zivid::toString(e) << std::endl;
return EXIT_FAILURE;
}
}
Zivid::Settings::Filters::Outlier::Enabled::yes
static const Enabled yes
On/enabled.
Definition: Settings.h:1364
Zivid::toString
ZIVID_API_EXPORT std::string toString(const std::exception &exception)
Get string representation of the exception
Zivid.h
Zivid::Settings2D::Gain
Analog gain in the camera
Definition: Settings2D.h:410
Zivid::Matrix< double, 4, 4 >
Zivid::Application
Manager class for Zivid
Definition: Application.h:99
Zivid::HandEye::calibrateEyeToHand
ZIVID_API_EXPORT CalibrationOutput calibrateEyeToHand(const std::vector< CalibrationInput > &input)
Performs eye-to-hand calibration.
Zivid::CaptureAssistant::SuggestSettingsParameters
SuggestSettingsParameters class is used to specify time constraint on total capture time for settings...
Definition: CaptureAssistant.h:119
Zivid::CloudVisualizer::show
ZIVID_VIS3D_EXPORT void show()
Show the visualization window
Pose.h
Zivid::CaptureAssistant::AmbientLightFrequency::none
Zivid::Camera::userData
ZIVID_API_EXPORT std::vector< uint8_t > userData() const
Read user data from camera
Zivid::RGBA8
Definition: Image.h:94
Zivid::Camera::userDataMaxSizeBytes
ZIVID_API_EXPORT size_t userDataMaxSizeBytes() const
Get the maximum number of bytes of user data that can be stored in the camera
Zivid::Application::createFileCamera
ZIVID_API_EXPORT Camera createFileCamera(const std::string &frameFile, const Settings &settings={})
Create a virtual camera to simulate Zivid measurements by reading data from a file
CaptureAssistant.h
Zivid::CaptureAssistant::suggestSettings
ZIVID_API_EXPORT std::vector< Settings > suggestSettings(Camera &camera, const SuggestSettingsParameters &suggestSettingsParameters)
Finds suggested settings for the current scene based on the SuggestSettingsParameters.
Zivid::CloudVisualizer::showMaximized
ZIVID_VIS3D_EXPORT void showMaximized()
Show the window in maximized mode
Zivid::Application::connectCamera
ZIVID_API_EXPORT Camera connectCamera(const Settings &settings={})
Connect to the next available Zivid camera
Zivid::Settings::ExposureTime
Exposure time for each single image in the measurement. Affects frame rate.
Definition: Settings.h:513
Exception.h
Zivid::Camera::setSettings
ZIVID_API_EXPORT void setSettings(Settings settings)
Update the camera settings
Zivid::Frame::save
ZIVID_API_EXPORT void save(const std::string &fileName) const
Save the frame to file
Zivid::Environment::dataPath
ZIVID_API_EXPORT std::string dataPath()
Get default location for sample data
Zivid::HDR::capture
ZIVID_API_EXPORT Frame capture(Camera &camera, const std::vector< Settings > &settings)
A convenience function to capture and merge frames.
Zivid::Settings
Settings for a Zivid camera
Definition: Settings.h:107
Zivid::Camera
Interface to one Zivid camera
Definition: Camera.h:113
Zivid::Settings::set
void set(const std::string &fullPath, const std::string &value)
Set a value from string by specifying the path
Zivid::CloudVisualizer::resetToFit
ZIVID_VIS3D_EXPORT void resetToFit()
Reset the camera so that the contents will fit in the window
Zivid::Camera::capture
ZIVID_API_EXPORT Frame capture()
Capture a single 3D frame
Detector.h
Zivid::Application::setDefaultComputeDevice
ZIVID_API_EXPORT void setDefaultComputeDevice(ComputeDevice device)
Set the default compute device to be used for new cameras
Zivid::Settings::Gain
Analog gain in the camera
Definition: Settings.h:2447
Zivid::HDR::combineFrames
Frame combineFrames(InputIt first, InputIt last)
Combine frames acquired with different camera settings
Definition: HDR.h:112
Zivid::CloudVisualizer::computeDevice
ZIVID_VIS3D_EXPORT ComputeDevice computeDevice()
Get the compute device associated with this view
Zivid::Settings2D::ExposureTime
Exposure time for the image.
Definition: Settings2D.h:316
Zivid::CloudVisualizer::run
ZIVID_VIS3D_EXPORT int run()
Run the event loop. Should be called to allow interaction with the point cloud
Zivid::HandEye::CalibrationInput
Binds together a robot pose and the detection result acquired from the pose
Definition: Calibrate.h:173
Zivid::Settings::Brightness
Brightness controls the light output from the projector.
Definition: Settings.h:403
Zivid::Frame
A frame captured by a Zivid camera
Definition: Frame.h:104
Zivid::Settings2D
2D Capture settings
Definition: Settings2D.h:107
Zivid::HandEye::Pose
Describes a robot pose
Definition: Pose.h:137
Zivid::Matrix::cbegin
ConstIterator cbegin() const
Iterator to the beginning of the matrix
Definition: Matrix.h:236
CloudVisualizer.h
Zivid::Settings::Filters::Gaussian::Enabled::yes
static const Enabled yes
On/enabled.
Definition: Settings.h:1015
Zivid::HandEye::detectFeaturePoints
ZIVID_API_EXPORT DetectionResult detectFeaturePoints(const PointCloud &cloud)
Detects feature points from a calibration object in a point cloud.
HDR.h
Zivid::Camera::writeUserData
ZIVID_API_EXPORT void writeUserData(const std::vector< uint8_t > &data)
Write user data to camera. The total number of writes supported depends on camera model and size of d...
Zivid::Settings::Iris
Iris (aperture) setting for the camera
Definition: Settings.h:2540
Calibrate.h
Zivid::Settings::Filters::Outlier::Threshold
Discard point if Euclidean distance to neighboring points is above the given value
Definition: Settings.h:1456
Zivid::Settings2D::Iris
Iris (aperture) setting for the camera
Definition: Settings2D.h:503
Application.h
Zivid::CloudVisualizer
Simple visualization component for point clouds (residing either on the Compute device or on the CPU)
Definition: CloudVisualizer.h:103