diff --git a/README.md b/README.md
index afad3939..b685439f 100644
--- a/README.md
+++ b/README.md
@@ -191,13 +191,23 @@ ROS_NAMESPACE=zivid_camera rosrun nodelet nodelet standalone zivid_camera/nodele
The following parameters can be specified when starting the driver. Note that all the parameters are
optional, and typically not required to set.
-For example, to launch the driver with `frame_id` specified, append `_frame_id:=camera1` to the
-rosrun command:
+For example, to run the zivid_camera driver with `frame_id` specified, append `_frame_id:=camera1` to the
+`rosrun` command:
```bash
ROS_NAMESPACE=zivid_camera rosrun zivid_camera zivid_camera_node _frame_id:=camera1
```
+Or, if using `roslaunch` specify the parameter using ``:
+
+```xml
+
+
+
+
+
+```
+
`file_camera_path` (string, default: "")
> Specify the path to a file camera to use instead of a real Zivid camera. This can be used to
> develop without access to hardware. The file camera returns the same point cloud for every capture.
@@ -219,6 +229,13 @@ ROS_NAMESPACE=zivid_camera rosrun zivid_camera zivid_camera_node _frame_id:=came
> 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
@@ -640,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
\ No newline at end of file
+[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
diff --git a/zivid_camera/src/zivid_camera.cpp b/zivid_camera/src/zivid_camera.cpp
index 74604eab..2a8df685 100644
--- a/zivid_camera/src/zivid_camera.cpp
+++ b/zivid_camera/src/zivid_camera.cpp
@@ -137,6 +137,9 @@ ZividCamera::ZividCamera(ros::NodeHandle& nh, ros::NodeHandle& priv)
priv_.param("use_latched_publisher_for_snr_image", use_latched_publisher_for_snr_image_, false);
priv_.param("use_latched_publisher_for_normals_xyz", use_latched_publisher_for_normals_xyz_, false);
+ bool update_firmware_automatically = true;
+ priv_.param("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());
@@ -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.");
+ }
}
}