Skip to content

Commit

Permalink
Use std_srvs/Empty instead of custom Zivid name
Browse files Browse the repository at this point in the history
The messages are equivalent, but std_srvs is also usable by other packages without having to build the driver (+ install SDK)
  • Loading branch information
dave992 committed Sep 23, 2024
1 parent 2b40856 commit 7521e35
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
5 changes: 3 additions & 2 deletions zivid_camera/include/zivid_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>
#include <std_srvs/Empty.h>

#include <image_transport/image_transport.h>

Expand Down Expand Up @@ -42,8 +43,8 @@ class ZividCamera
bool cameraInfoModelNameServiceHandler(CameraInfoModelName::Request& req, CameraInfoModelName::Response& res);
bool cameraInfoSerialNumberServiceHandler(CameraInfoSerialNumber::Request& req,
CameraInfoSerialNumber::Response& res);
bool captureServiceHandler(Capture::Request& req, Capture::Response& res);
bool capture2DServiceHandler(Capture2D::Request& req, Capture2D::Response& res);
bool captureServiceHandler(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
bool capture2DServiceHandler(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
bool captureAssistantSuggestSettingsServiceHandler(CaptureAssistantSuggestSettings::Request& req,
CaptureAssistantSuggestSettings::Response& res);
bool loadSettingsFromFileServiceHandler(LoadSettingsFromFile::Request& req, LoadSettingsFromFile::Response&);
Expand Down
4 changes: 2 additions & 2 deletions zivid_camera/src/zivid_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,7 @@ bool ZividCamera::cameraInfoSerialNumberServiceHandler(zivid_camera::CameraInfoS
return true;
}

bool ZividCamera::captureServiceHandler(Capture::Request&, Capture::Response&)
bool ZividCamera::captureServiceHandler(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
{
ROS_DEBUG_STREAM(__func__);

Expand All @@ -354,7 +354,7 @@ bool ZividCamera::captureServiceHandler(Capture::Request&, Capture::Response&)
return true;
}

bool ZividCamera::capture2DServiceHandler(Capture2D::Request&, Capture2D::Response&)
bool ZividCamera::capture2DServiceHandler(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
{
ROS_DEBUG_STREAM(__func__);

Expand Down

0 comments on commit 7521e35

Please sign in to comment.