Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

F3-5443: Add service for resetting the camera exposure #64

Merged
merged 1 commit into from
Jul 16, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 11 additions & 5 deletions nodes/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,14 +93,19 @@ class UsbCamNode

UsbCam cam_;

ros::ServiceServer service_start_, service_stop_, service_auto_reset_exposure_;
ros::ServiceServer service_start_, service_stop_, service_auto_reset_exposure_, reset_exposure_;

bool service_start_cap(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res )
{
cam_.start_capturing();
return true;
}

bool reset_exposure_call(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res )
{
resetExposureSettings();
return true;
}

bool service_stop_cap( std_srvs::Empty::Request &req, std_srvs::Empty::Response &res )
{
Expand Down Expand Up @@ -163,6 +168,7 @@ class UsbCamNode
// create Services
service_start_ = node_.advertiseService("start_capture", &UsbCamNode::service_start_cap, this);
service_stop_ = node_.advertiseService("stop_capture", &UsbCamNode::service_stop_cap, this);
reset_exposure_ = node_.advertiseService("manual_reset_exposure", &UsbCamNode::reset_exposure_call, this);
service_auto_reset_exposure_ = node_.advertiseService("reset_exposure", &UsbCamNode::service_auto_reset_exposure, this);

if (!serial_number_.empty())
Expand Down Expand Up @@ -387,8 +393,7 @@ class UsbCamNode
{
if (enable_auto_reset_exposure_)
{
std::thread t1(&UsbCamNode::resetExposureSettings, this);
t1.detach();
resetExposureSettings();
}
}

Expand All @@ -400,10 +405,8 @@ class UsbCamNode
if (cam_.is_capturing() && !cam_.is_changing_config()) {
if (!take_and_send_image()) ROS_WARN("USB camera did not respond in time.");
}
ros::spinOnce();
heartbeat_.update();
loop_rate.sleep();

}
return true;
}
Expand All @@ -414,6 +417,9 @@ class UsbCamNode
int main(int argc, char **argv)
{
ros::init(argc, argv, "usb_cam");
// Will need more threads if we add more callbacks
ros::AsyncSpinner spinner{ 2 };

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Add some kind of note here that if we add another callback type without adding another thread, there could be weird threading issues

spinner.start();
usb_cam::UsbCamNode a;
a.spin();
return EXIT_SUCCESS;
Expand Down
Loading