Skip to content

Commit d94f99a

Browse files
Added parameter for device throughput limit
1 parent fe5cb56 commit d94f99a

File tree

5 files changed

+21
-0
lines changed

5 files changed

+21
-0
lines changed

spinnaker_camera_driver/include/spinnaker_camera_driver/SpinnakerCamera.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -159,6 +159,7 @@ class SpinnakerCamera
159159
* \param id serial number for the camera. Should be something like 10491081.
160160
*/
161161
void setDesiredCamera(const uint32_t& id);
162+
void setThroughputLimit(const uint32_t& limit);
162163

163164
void setGain(const float& gain);
164165
int getHeightMax();
@@ -198,6 +199,8 @@ class SpinnakerCamera
198199
unsigned int packet_size_;
199200
/// GigE packet delay:
200201
unsigned int packet_delay_;
202+
/// GigE throughput limit:
203+
unsigned int throughput_limit_;
201204

202205
uint64_t timeout_;
203206

spinnaker_camera_driver/include/spinnaker_camera_driver/camera.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ class Camera
6565
virtual void setGain(const float& gain);
6666
int getHeightMax();
6767
int getWidthMax();
68+
void setThroughputLimit(const int& limit);
6869

6970
Spinnaker::GenApi::CNodePtr
7071
readProperty(const Spinnaker::GenICam::gcstring property_name);

spinnaker_camera_driver/src/SpinnakerCamera.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,12 @@ void SpinnakerCamera::setNewConfiguration(const spinnaker_camera_driver::Spinnak
9696
}
9797
} // end setNewConfiguration
9898

99+
void SpinnakerCamera::setThroughputLimit(const uint32_t& limit)
100+
{
101+
if (camera_)
102+
camera_->setThroughputLimit(limit);
103+
}
104+
99105
void SpinnakerCamera::setGain(const float& gain)
100106
{
101107
if (camera_)
@@ -377,6 +383,7 @@ void SpinnakerCamera::grabImage(sensor_msgs::Image* image, const std::string& fr
377383
Spinnaker::GenICam::gcstring bayer_gb_str = "BayerGB";
378384
Spinnaker::GenICam::gcstring bayer_bg_str = "BayerBG";
379385

386+
380387
// if(isColor_ && bayer_format != NONE)
381388
if (color_filter_ptr->GetCurrentEntry() != color_filter_ptr->GetEntryByName("None"))
382389
{

spinnaker_camera_driver/src/camera.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -242,6 +242,12 @@ void Camera::setGain(const float& gain)
242242
setProperty(node_map_, "Gain", static_cast<float>(gain));
243243
}
244244

245+
void Camera::setThroughputLimit(const int& limit)
246+
{
247+
setProperty(node_map_, "DeviceLinkThroughputLimit", limit);
248+
}
249+
250+
245251
/*
246252
void Camera::setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
247253
{

spinnaker_camera_driver/src/nodelet.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -302,6 +302,7 @@ class SpinnakerCameraNodelet : public nodelet::Nodelet
302302
pnh.param<int>("packet_size", packet_size_, 1400);
303303
pnh.param<bool>("auto_packet_size", auto_packet_size_, true);
304304
pnh.param<int>("packet_delay", packet_delay_, 4000);
305+
pnh.param<int>("throughput_limit", throughput_limit_, 125000000);
305306

306307
// TODO(mhosmar): Set GigE parameters:
307308
// spinnaker_.setGigEParameters(auto_packet_size_, packet_size_, packet_delay_);
@@ -518,6 +519,7 @@ class SpinnakerCameraNodelet : public nodelet::Nodelet
518519
NODELET_DEBUG("Connected to camera.");
519520

520521
// Set last configuration, forcing the reconfigure level to stop
522+
spinnaker_.setThroughputLimit(throughput_limit_);
521523
spinnaker_.setNewConfiguration(config_, SpinnakerCamera::LEVEL_RECONFIGURE_STOP);
522524

523525
// Set the timeout for grabbing images.
@@ -719,6 +721,8 @@ class SpinnakerCameraNodelet : public nodelet::Nodelet
719721
int packet_size_;
720722
/// GigE packet delay:
721723
int packet_delay_;
724+
/// GigE throughput limit:
725+
int throughput_limit_;
722726

723727
/// Configuration:
724728
spinnaker_camera_driver::SpinnakerConfig config_;

0 commit comments

Comments
 (0)