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

Grabbing strategy/issue28 #56

Merged
merged 3 commits into from
Dec 15, 2020
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
6 changes: 5 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,9 @@ This is a list of the supported functionality accesible through ROS services, wh
* Acquisition Frame Rate
* Resulting Frame Rate
* Trigger Timeout
* grabbing Timeout
* Grabbing Timeout
- Grabbing Strategy
- Output Queue Size

### Digital I/O Control
* Line Selector
Expand Down Expand Up @@ -153,6 +155,8 @@ Service Name | Notes
/pylon_camera_node/stop_grabbing | -
/pylon_camera_node/set_grab_timeout | -
/pylon_camera_node/set_trigger_timeout | -
/pylon_camera_node/set_grabbing_strategy | value : 0 = GrabStrategy_OneByOne, 1 = GrabStrategy_LatestImageOnly, 2 = GrabStrategy_LatestImages
/pylon_camera_node/set_output_queue_size | -

## 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 @@ -19,6 +19,8 @@
# - set_gamma_selector (value: 0 = User, 1 = sRGB)
# - set_grab_timeout (unit : ms)
# - set_trigger_timeout (unit : ms)
# - set_grabbing_strategy : set 0 = GrabStrategy_OneByOne, set 1 = GrabStrategy_LatestImageOnly, set 2 = GrabStrategy_LatestImages


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


0.16.6 (2020-10-19)
-------------------
* Add below listed new ROS services :
- set_grabbing_strategy.
- set_output_queue_size.
* Make camera grabbing strategy configurable parameters in default.yaml

0.16.5 (2020-10-15)
-------------------
* Add below listed new ROS services :
Expand Down
5 changes: 5 additions & 0 deletions pylon_camera/README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,9 @@ The following settings do **NOT** have to be set. Each camera has default values
- **grab_timeout**
The camera grab timout in ms

- **grab_strategy**
The camera grabbing strategy.


******
**Usage**
Expand Down Expand Up @@ -169,6 +172,8 @@ Some of the ROS service use integer values for as a commands, below are a list o

- **set_gamma_selector** ROS Service: 0 = User, 1 = sRGB

- **set_grabbing_strategy** ROS Service: 0 = GrabStrategy_OneByOne, 1 = GrabStrategy_LatestImageOnly, 2 = GrabStrategy_LatestImages

******
**Questions**
******
Expand Down
6 changes: 6 additions & 0 deletions pylon_camera/config/default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,12 @@ frame_rate: 5.0
trigger_timeout: 5000 # in ms
grab_timeout: 500 # in ms

# Camera grab strategy
# 0 : GrabStrategy_OneByOne
# 1 : GrabStrategy_LatestImageOnly
# 2 : GrabStrategy_LatestImages
grab_strategy : 0


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

int trigger_timeout;

template <typename CameraTraitT>
PylonCameraImpl<CameraTraitT>::PylonCameraImpl(Pylon::IPylonDevice* device) :
PylonCamera(),
Expand Down Expand Up @@ -179,7 +177,8 @@ std::string PylonCameraImpl<CameraTraitT>::currentROSEncoding() const
ROS_ERROR_STREAM("No ROS equivalent to GenApi encoding");
cam_->StopGrabbing();
setImageEncoding(gen_api_encoding);
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
//return "NO_ENCODING";
}
return ros_encoding;
Expand Down Expand Up @@ -359,8 +358,9 @@ bool PylonCameraImpl<CameraTraitT>::startGrabbing(const PylonCameraParameter& pa
}
if (error) return false;
}

cam_->StartGrabbing();
grab_strategy = parameters.grab_strategy_;
//cam_->StartGrabbing();
grabbingStarting();
user_output_selector_enums_ = detectAndCountNumUserOutputs();
device_user_id_ = cam_->DeviceUserID.GetValue();
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
Expand Down Expand Up @@ -641,7 +641,8 @@ std::string PylonCameraImpl<CameraTraitT>::setImageEncoding(const std::string& r
if ( GenApi::IsAvailable(cam_->PixelFormat) )
{
GenApi::INodeMap& node_map = cam_->GetNodeMap();
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
cam_->StopGrabbing();
GenApi::CEnumerationPtr(node_map.GetNode("PixelFormat"))->FromString(gen_api_encoding.c_str());
return "done";
Expand Down Expand Up @@ -784,7 +785,8 @@ bool PylonCameraImpl<CameraTraitT>::setROI(const sensor_msgs::RegionOfInterest t
cam_->OffsetX.SetValue(offset_x_to_set);
cam_->OffsetY.SetValue(offset_y_to_set);
reached_roi = currentROI();
cam_->StartGrabbing();
grabbingStarting();
//cam_->StartGrabbing();

img_cols_ = static_cast<size_t>(cam_->Width.GetValue());
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
Expand Down Expand Up @@ -842,7 +844,8 @@ bool PylonCameraImpl<CameraTraitT>::setBinningX(const size_t& target_binning_x,
}
cam_->BinningHorizontal.SetValue(binning_x_to_set);
reached_binning_x = currentBinningX();
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
img_cols_ = static_cast<size_t>(cam_->Width.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
}
Expand Down Expand Up @@ -889,7 +892,8 @@ bool PylonCameraImpl<CameraTraitT>::setBinningY(const size_t& target_binning_y,
}
cam_->BinningVertical.SetValue(binning_y_to_set);
reached_binning_y = currentBinningY();
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
}
Expand Down Expand Up @@ -2761,11 +2765,20 @@ std::string PylonCameraImpl<CameraTraitT>::triggerDeviceReset()
}

template <typename CameraTraitT>
std::string PylonCameraImpl<CameraTraitT>::grabbingStarting()
std::string PylonCameraImpl<CameraTraitT>::grabbingStarting() const
{
try
{
cam_->StartGrabbing();
if(grab_strategy == 0) {
cam_->StartGrabbing(Pylon::EGrabStrategy::GrabStrategy_OneByOne);
} else if (grab_strategy == 1) {
cam_->StartGrabbing(Pylon::EGrabStrategy::GrabStrategy_LatestImageOnly);
} else if (grab_strategy == 2) {
cam_->StartGrabbing(Pylon::EGrabStrategy::GrabStrategy_LatestImages);
} else {
cam_->StartGrabbing(Pylon::EGrabStrategy::GrabStrategy_OneByOne);
}

return "done";

}
Expand Down Expand Up @@ -2803,7 +2816,7 @@ std::string PylonCameraImpl<CameraTraitT>::setMaxTransferSize(const int& maxTran
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while starting the free run mode occurred:" << e.GetDescription());
ROS_ERROR_STREAM("An exception while setting the max transfer size occurred:" << e.GetDescription());
grabbingStarting();
return e.GetDescription();
}
Expand All @@ -2814,6 +2827,36 @@ float PylonCameraImpl<CameraTraitT>::getTemperature(){
return 0.0;
}


template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setGrabbingStrategy(const int& strategy) {
if (strategy >= 0 && strategy <= 2){
grab_strategy = strategy;
return true;
} else {
return false;
}

}

template <typename CameraTraitT>
std::string PylonCameraImpl<CameraTraitT>::setOutputQueueSize(const int& size) {
if (size >= 0 && size <= cam_->MaxNumBuffer.GetValue()){
try {
cam_->OutputQueueSize.SetValue(size);
return "done";
} catch ( const GenICam::GenericException &e ){
ROS_ERROR_STREAM("An exception while setting the output queue size occurred:" << e.GetDescription());
return e.GetDescription();
}
} else {
return "requested output queue size is out side the limits of : 0-"+std::to_string(cam_->MaxNumBuffer.GetValue());
}

}

} // namespace pylon_camera



#endif // PYLON_CAMERA_INTERNAL_BASE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,8 @@ bool PylonGigECamera::setAutoflash(const std::map<int, bool> flash_on_lines)
{
try
{
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
cam_->StopGrabbing();
ROS_INFO("Executing SetAutoFlash: %i -> %i", p.first, p.second);
if (p.first == 2)
Expand Down Expand Up @@ -146,7 +147,8 @@ bool PylonGigECamera::applyCamSpecificStartupSettings(const PylonCameraParameter
{
try
{
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
cam_->StopGrabbing();
if (parameters.startup_user_set_ == "Default")
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,8 @@ bool PylonUSBCamera::applyCamSpecificStartupSettings(const PylonCameraParameter&
{
try
{
cam_->StartGrabbing();
//cam_->StartGrabbing();
grabbingStarting();
cam_->StopGrabbing();
if (parameters.startup_user_set_ == "Default")
{
Expand Down
6 changes: 5 additions & 1 deletion pylon_camera/include/pylon_camera/internal/pylon_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ class PylonCameraImpl : public PylonCamera

virtual std::string triggerDeviceReset();

virtual std::string grabbingStarting();
virtual std::string grabbingStarting() const;

virtual std::string grabbingStopping();

Expand All @@ -255,6 +255,10 @@ class PylonCameraImpl : public PylonCamera

virtual float getTemperature();

virtual bool setGrabbingStrategy(const int& strategy);

virtual std::string setOutputQueueSize(const int& size);

protected:
typedef typename CameraTraitT::CBaslerInstantCameraT CBaslerInstantCameraT;
typedef typename CameraTraitT::ExposureAutoEnums ExposureAutoEnums;
Expand Down
31 changes: 30 additions & 1 deletion pylon_camera/include/pylon_camera/pylon_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -763,7 +763,7 @@ class PylonCamera
* start camera aqcuisition
* @return error message if an error occurred or done message otherwise.
*/
virtual std::string grabbingStarting() = 0;
virtual std::string grabbingStarting() const = 0;

/**
* stop camera aqcuisition
Expand Down Expand Up @@ -792,12 +792,26 @@ class PylonCamera
*/
virtual std::string gammaEnable(const bool& enable) = 0;


/**
* set the camera grapping strategy
* @param strategy : 0 = GrabStrategy_OneByOne, 1 = GrabStrategy_LatestImageOnly, 2 = GrabStrategy_LatestImages
* @return error message if an error occurred or done message otherwise.
*/
virtual bool setGrabbingStrategy(const int& strategy) = 0;

/**
* returns the current internal camera temperature
* @return 0.0 if error or unknown
*/
virtual float getTemperature() = 0;

/**
* set The size of the grab result buffer output queue
* @return error message if an error occurred or done message otherwise.
*/
virtual std::string setOutputQueueSize(const int& size) = 0;

virtual ~PylonCamera();
protected:
/**
Expand Down Expand Up @@ -850,6 +864,21 @@ class PylonCamera
*/
bool is_ready_;

/**
* Camera trigger timeout in ms
*/
int trigger_timeout;

/**
* Camera grab strategy
* 0 = GrabStrategy_OneByOne
* 1 = GrabStrategy_LatestImageOnly
* 2 = GrabStrategy_LatestImages
*/
int grab_strategy ;



/**
* True if the extended binary exposure search is running.
*/
Expand Down
18 changes: 18 additions & 0 deletions pylon_camera/include/pylon_camera/pylon_camera_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -938,6 +938,22 @@ class PylonCameraNode
*/
bool setTriggerTimeoutCallback(camera_control_msgs::SetIntegerValue::Request &req, camera_control_msgs::SetIntegerValue::Response &res);

/**
* Service callback for setting the camera grabbing strategy
* @param req request
* @param res response
* @return true on success
*/
bool setGrabbingStrategyCallback(camera_control_msgs::SetIntegerValue::Request &req, camera_control_msgs::SetIntegerValue::Response &res);

/**
* Service callback for setting the size of the grab result buffer output queue.
* @param req request
* @param res response
* @return true on success
*/
bool setOutputQueueSizeCallback(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 @@ -986,6 +1002,8 @@ class PylonCameraNode
ros::ServiceServer gamma_enable_srv;
ros::ServiceServer set_grab_timeout_srv;
ros::ServiceServer set_trigger_timeout_srv;
ros::ServiceServer set_grabbing_strategy_srv;
ros::ServiceServer set_output_queue_size_srv;

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

Expand Down
8 changes: 8 additions & 0 deletions pylon_camera/include/pylon_camera/pylon_camera_parameter.h
Original file line number Diff line number Diff line change
Expand Up @@ -316,6 +316,14 @@ class PylonCameraParameter
*/
int trigger_timeout_;

/**
* Camera grab strategy
* 0 = GrabStrategy_OneByOne
* 1 = GrabStrategy_LatestImageOnly
* 2 = GrabStrategy_LatestImages
*/
int grab_strategy_;



protected:
Expand Down
Loading