Skip to content
New issue

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

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

Already on GitHub? # to your account

make camera trigger and grib timeout configurable - issue 29 #55

Merged
Show file tree
Hide file tree
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
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@ This is a list of the supported functionality accesible through ROS services, wh
* Auto Exposure Time Upper Limit
* Acquisition Frame Rate
* Resulting Frame Rate
* Trigger Timeout
* grabbing Timeout

### Digital I/O Control
* Line Selector
Expand Down Expand Up @@ -149,6 +151,8 @@ Service Name | Notes
/pylon_camera_node/set_trigger_source | value : 0 = Software, 1 = Line1, 2 = Line3, 3 = Line4, 4 = Action1 (only selected GigE Camera)
/pylon_camera_node/start_grabbing | -
/pylon_camera_node/stop_grabbing | -
/pylon_camera_node/set_grab_timeout | -
/pylon_camera_node/set_trigger_timeout | -

## Image pixel encoding

Expand Down
2 changes: 2 additions & 0 deletions camera_control_msgs/srv/SetIntegerValue.srv
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
# - select_user_set ROS service (value : 0 = Default, 1 = UserSet1, 2 = UserSet2, 3 = UserSet3, 4 = HighGain, 5 = AutoFunctions, 6 = ColorRaw)
# - select_default_user_set ROS service (value : 0 = Default, 1 = UserSet1, 2 = UserSet2, 3 = UserSet3, 4 = HighGain, 5 = AutoFunctions, 6 = ColorRaw)
# - set_gamma_selector (value: 0 = User, 1 = sRGB)
# - set_grab_timeout (unit : ms)
# - set_trigger_timeout (unit : ms)

int32 value # value to be setted
---
Expand Down
7 changes: 7 additions & 0 deletions pylon_camera/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package pylon_camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.16.5 (2020-10-15)
-------------------
* Add below listed new ROS services :
- set_grab_timeout (in ms).
- set_trigger_timeout (in ms).
* Make camera grab and trigger timeout configurable parameters in default.yaml

0.16.4 (2019-09-30)
-------------------
* Add below listed new ROS services :
Expand Down
6 changes: 6 additions & 0 deletions pylon_camera/README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,12 @@ The following settings do **NOT** have to be set. Each camera has default values
- **gige/inter_pkg_delay**
The inter-package delay in ticks. Only used for GigE cameras. To prevent lost frames it should be greater 0. For most of GigE-Cameras, a value of 1000 is reasonable. For GigE-Cameras used on a RaspberryPI this value should be set to 11772.

- **trigger_timeout**
The camera trigger timout in ms

- **grab_timeout**
The camera grab timout in ms


******
**Usage**
Expand Down
4 changes: 4 additions & 0 deletions pylon_camera/config/default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@ camera_info_url: ""
# Calling the GrabImages-Action can result in a higher framerate
frame_rate: 5.0

trigger_timeout: 5000 # in ms
grab_timeout: 500 # in ms


# Mode of camera's shutter.
# The supported modes are "rolling", "global" and "global_reset"
# Default value is "" (empty) means default_shutter_mode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
namespace pylon_camera
{

int trigger_timeout;

template <typename CameraTraitT>
PylonCameraImpl<CameraTraitT>::PylonCameraImpl(Pylon::IPylonDevice* device) :
PylonCamera(),
Expand Down Expand Up @@ -366,8 +368,8 @@ bool PylonCameraImpl<CameraTraitT>::startGrabbing(const PylonCameraParameter& pa
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();

//grab_timeout_ = exposureTime().GetMax() * 1.05;
grab_timeout_ = 500; // grab timeout = 500 ms

grab_timeout_ = parameters.grab_timeout_; // grab timeout = 500 ms
trigger_timeout = parameters.trigger_timeout_;
// grab one image to be sure, that the communication is successful
Pylon::CGrabResultPtr grab_result;
grab(grab_result);
Expand Down Expand Up @@ -473,13 +475,13 @@ bool PylonCameraImpl<CameraTrait>::grab(Pylon::CGrabResultPtr& grab_result)

try
{
int timeout = 5000; // ms
//int timeout = 5000; // ms
// WaitForFrameTriggerReady to prevent trigger signal to get lost
// this could happen, if 2xExecuteSoftwareTrigger() is only followed by 1xgrabResult()
// -> 2nd trigger might get lost
if ((cam_->TriggerMode.GetValue() == TriggerModeEnums::TriggerMode_On))
{
if ( cam_->WaitForFrameTriggerReady(timeout, Pylon::TimeoutHandling_ThrowException) )
if ( cam_->WaitForFrameTriggerReady(trigger_timeout, Pylon::TimeoutHandling_ThrowException) )
{
cam_->ExecuteSoftwareTrigger();
}
Expand Down
21 changes: 20 additions & 1 deletion pylon_camera/include/pylon_camera/pylon_camera_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -922,6 +922,22 @@ class PylonCameraNode
*/
std::string gammaEnable(const int& enable);

/**
* Service callback for setting the camera grab timeout in ms
* @param req request
* @param res response
* @return true on success
*/
bool setGrabTimeoutCallback(camera_control_msgs::SetIntegerValue::Request &req, camera_control_msgs::SetIntegerValue::Response &res);

/**
* Service callback for setting the camera trigger timeout in ms
* @param req request
* @param res response
* @return true on success
*/
bool setTriggerTimeoutCallback(camera_control_msgs::SetIntegerValue::Request &req, camera_control_msgs::SetIntegerValue::Response &res);

ros::NodeHandle nh_;
PylonCameraParameter pylon_camera_parameter_set_;
ros::ServiceServer set_binning_srv_;
Expand Down Expand Up @@ -967,7 +983,10 @@ class PylonCameraNode
ros::ServiceServer stop_grabbing_srv_;
ros::ServiceServer set_max_transfer_size_srv_;
ros::ServiceServer set_gamma_selector_srv;
ros::ServiceServer gamma_enable_srv;
ros::ServiceServer gamma_enable_srv;
ros::ServiceServer set_grab_timeout_srv;
ros::ServiceServer set_trigger_timeout_srv;

std::vector<ros::ServiceServer> set_user_output_srvs_;

// DNB component status publisher
Expand Down
12 changes: 12 additions & 0 deletions pylon_camera/include/pylon_camera/pylon_camera_parameter.h
Original file line number Diff line number Diff line change
Expand Up @@ -305,6 +305,18 @@ class PylonCameraParameter
* Only supported for GigE cameras. Default: true
*/
bool auto_flash_line_3_;

/**
* camera grab timeout in ms
*/
int grab_timeout_;

/**
* camera trigger timeout in ms
*/
int trigger_timeout_;



protected:
/**
Expand Down
35 changes: 34 additions & 1 deletion pylon_camera/src/pylon_camera/pylon_camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,12 @@ PylonCameraNode::PylonCameraNode()
gamma_enable_srv(nh_.advertiseService("gamma_enable",
&PylonCameraNode::gammaEnableCallback,
this)),
set_grab_timeout_srv(nh_.advertiseService("set_grab_timeout",
&PylonCameraNode::setGrabTimeoutCallback,
this)),
set_trigger_timeout_srv(nh_.advertiseService("set_trigger_timeout",
&PylonCameraNode::setTriggerTimeoutCallback,
this)),
set_user_output_srvs_(),
pylon_camera_(nullptr),
it_(new image_transport::ImageTransport(nh_)),
Expand Down Expand Up @@ -2908,6 +2914,33 @@ std::string PylonCameraNode::gammaEnable(const int& enable)
return pylon_camera_->gammaEnable(enable) ;
}


bool PylonCameraNode::setGrabTimeoutCallback(camera_control_msgs::SetIntegerValue::Request &req, camera_control_msgs::SetIntegerValue::Response &res)
{
grabbingStopping();
try {
pylon_camera_parameter_set_.grab_timeout_ = req.value;
res.success = true;
} catch (...){
res.success = false;
}
grabbingStarting(); // start grappiong is required to set the new trigger timeout
return true;
}

bool PylonCameraNode::setTriggerTimeoutCallback(camera_control_msgs::SetIntegerValue::Request &req, camera_control_msgs::SetIntegerValue::Response &res)
{
grabbingStopping();
try {
pylon_camera_parameter_set_.trigger_timeout_ = req.value;
res.success = true;
} catch (...){
res.success = false;
}
grabbingStarting(); // start grappiong is required to set the new trigger timeout
return true;
}

void PylonCameraNode::currentParamPub()
{
boost::lock_guard<boost::recursive_mutex> lock(grab_mutex_);
Expand Down Expand Up @@ -3004,4 +3037,4 @@ PylonCameraNode::~PylonCameraNode()
}
}

} // namespace pylon_camera
} // namespace pylon_camera
12 changes: 11 additions & 1 deletion pylon_camera/src/pylon_camera/pylon_camera_parameter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,9 @@ PylonCameraParameter::PylonCameraParameter() :
inter_pkg_delay_(1000),
startup_user_set_(""),
shutter_mode_(SM_DEFAULT),
auto_flash_(false)
auto_flash_(false),
grab_timeout_(500),
trigger_timeout_(5000)
{}

PylonCameraParameter::~PylonCameraParameter()
Expand Down Expand Up @@ -257,6 +259,14 @@ void PylonCameraParameter::readFromRosParameterServer(const ros::NodeHandle& nh)
{
nh.getParam("startup_user_set", startup_user_set_);
}
if ( nh.hasParam("grab_timeout") )
{
nh.getParam("grab_timeout", grab_timeout_);
}
if ( nh.hasParam("trigger_timeout") )
{
nh.getParam("trigger_timeout", trigger_timeout_);
}

nh.param<bool>("auto_flash", auto_flash_, false);
nh.param<bool>("auto_flash_line_2", auto_flash_line_2_, true);
Expand Down