Skip to content

Commit

Permalink
Add launch parameter to disable automatic camera firmware update
Browse files Browse the repository at this point in the history
By default the Zivid ROS driver always updates the firmware of the
camera. Some have expressed a desire to disable this behavior, so here
we add a launch parameter that can disable this feature. Then the camera
must be updated manually, fex in Zivid Studio or via
ZividFirmwareUpdater.
  • Loading branch information
apartridge committed Nov 8, 2021
1 parent 67a175b commit abacf6e
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 6 deletions.
10 changes: 9 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -229,6 +229,13 @@ Or, if using `roslaunch` specify the parameter using `<param>`:
> the command line or rosparam the serial number must be prefixed with a colon (`:12345`).
> This parameter is optional. By default the driver will connect to the first available camera.
`update_firmware_automatically` (bool, default: true)
> Specify if the firmware of the connected camera should be automatically updated to the correct
> version when the Zivid ROS driver starts. If set to false, if the firmware version is out of date
> then camera must be manually updated, for example using Zivid Studio or `ZividFirmwareUpdater`.
> Read more about [firmware update in our knowledgebase][firmware-update-kb-url].
> This parameter is optional, and by default it is true.
## Services

### capture_assistant/suggest_settings
Expand Down Expand Up @@ -650,4 +657,5 @@ grant agreement No 732287. For more information, visit [rosin-project.eu](http:/
[zivid-knowledge-base-url]: https://support.zivid.com
[zivid-software-installation-url]: https://support.zivid.com/latest/getting-started/software-installation.html
[install-opencl-drivers-ubuntu-url]: https://support.zivid.com/latest/getting-started/software-installation/gpu/install-opencl-drivers-ubuntu.html
[hdr-getting-good-point-clouds-url]: https://support.zivid.com/latest/academy/camera/capturing-high-quality-point-clouds/getting-the-right-exposure-for-good-point-clouds.html
[hdr-getting-good-point-clouds-url]: https://support.zivid.com/latest/academy/camera/capturing-high-quality-point-clouds/getting-the-right-exposure-for-good-point-clouds.html
[firmware-update-kb-url]: https://support.zivid.com/latest/academy/camera/firmware-update.html
23 changes: 18 additions & 5 deletions zivid_camera/src/zivid_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,9 @@ ZividCamera::ZividCamera(ros::NodeHandle& nh, ros::NodeHandle& priv)
priv_.param<bool>("use_latched_publisher_for_snr_image", use_latched_publisher_for_snr_image_, false);
priv_.param<bool>("use_latched_publisher_for_normals_xyz", use_latched_publisher_for_normals_xyz_, false);

bool update_firmware_automatically = true;
priv_.param<bool>("update_firmware_automatically", update_firmware_automatically, update_firmware_automatically);

if (file_camera_mode)
{
ROS_INFO("Creating file camera from file '%s'", file_camera_path.c_str());
Expand Down Expand Up @@ -181,11 +184,21 @@ ZividCamera::ZividCamera(ros::NodeHandle& nh, ros::NodeHandle& priv)

if (!Zivid::Firmware::isUpToDate(camera_))
{
ROS_INFO("The camera firmware is not up-to-date, starting update");
Zivid::Firmware::update(camera_, [](double progress, const std::string& state) {
ROS_INFO(" [%.0f%%] %s", progress, state.c_str());
});
ROS_INFO("Firmware update completed");
if (update_firmware_automatically)
{
ROS_INFO("The camera firmware is not up-to-date, and update_firmware_automatically is true, starting update");
Zivid::Firmware::update(camera_, [](double progress, const std::string& state) {
ROS_INFO(" [%.0f%%] %s", progress, state.c_str());
});
ROS_INFO("Firmware update completed");
}
else
{
ROS_ERROR("The camera firmware is not up-to-date, and update_firmware_automatically is false. Throwing error.");
throw std::runtime_error("The firmware on camera '" + camera_.info().serialNumber().value() +
"' is not up to date. The launch parameter update_firmware_automatically "
"is set to false. Please update the firmware on this camera manually.");
}
}
}

Expand Down

0 comments on commit abacf6e

Please sign in to comment.