Skip to content

Commit

Permalink
Merge pull request #131 from neufieldrobotics/dev
Browse files Browse the repository at this point in the history
Adding docker credentials to overcome rate limits, adding compatibili…
  • Loading branch information
mithundiddi authored Jun 20, 2021
2 parents f6ab290 + 8d03e96 commit 9c96330
Show file tree
Hide file tree
Showing 5 changed files with 35 additions and 49 deletions.
1 change: 1 addition & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ matrix:
env : DOCKER_IMAGE=arm64v8/ros:melodic-perception-bionic SPINNAKER_VERSION=2.0.0.147

before_install:
- echo "$DOCKER_PASSWORD" | docker login -u "$DOCKER_USERNAME" --password-stdin
- docker pull $DOCKER_IMAGE

script:
Expand Down
18 changes: 9 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,16 @@ These are the ros drivers for running the Pt Grey (FLIR) cameras that use the Sp
## Compatibility Matrix
| Spinnaker | Architecture | Ubnuntu 16.04 Xenial +<br>ROS Kinetic | Ubnuntu 18.04 Bionic +<br>ROS Melodic | Ubnuntu 20.04 Focal +<br>ROS Noetic |
|-----------|:------------:|:--------------------------------------:|:-------------------------------------:|:-----------------------------------:|
| 1.17.0.23 | AMD64 | :heavy_check_mark: |:heavy_minus_sign: |:heavy_minus_sign: |
| 1.17.0.23 | ARM64 | :heavy_check_mark: |:heavy_minus_sign: |:heavy_minus_sign: |
| 1.24.0.60 | AMD64 | :heavy_check_mark: |:heavy_minus_sign: |:heavy_minus_sign: |
| 1.24.0.60 | ARM64 | :heavy_check_mark: |:heavy_minus_sign: |:heavy_minus_sign: |
| 2.0.0.147 | AMD64 | :heavy_check_mark: |:white_check_mark: |:heavy_minus_sign: |
| 2.0.0.147 | ARM64 | :heavy_check_mark: | |:heavy_minus_sign: |
| 2.2.0.48 | AMD64 | :heavy_minus_sign: |:heavy_check_mark: | |
| 1.17.0.23 | AMD64 | :heavy_check_mark: | :heavy_minus_sign: | :heavy_minus_sign: |
| 1.17.0.23 | ARM64 | :heavy_check_mark: | :heavy_minus_sign: | :heavy_minus_sign: |
| 1.24.0.60 | AMD64 | :heavy_check_mark: | :heavy_minus_sign: | :heavy_minus_sign: |
| 1.24.0.60 | ARM64 | :heavy_check_mark: | :heavy_minus_sign: | :heavy_minus_sign: |
| 2.0.0.147 | AMD64 | :heavy_check_mark: | :white_check_mark: | :heavy_minus_sign: |
| 2.0.0.147 | ARM64 | :heavy_check_mark: | | :heavy_minus_sign: |
| 2.2.0.48 | AMD64 | :heavy_minus_sign: | :heavy_check_mark: | :white_check_mark: |
| 2.2.0.48 | ARM64 | :heavy_minus_sign: | | |
| 2.3.0.77 | AMD64 | :heavy_minus_sign: | | |
| 2.3.0.77 | ARM64 | :heavy_minus_sign: | | |
| 2.3.0.77 | AMD64 | :heavy_minus_sign: | | :x: |
| 2.3.0.77 | ARM64 | :heavy_minus_sign: | :x: | |

:heavy_check_mark: Tested
:heavy_minus_sign: Not Applicable
Expand Down
2 changes: 0 additions & 2 deletions include/spinnaker_sdk_camera_driver/capture.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,6 @@ namespace acquisition {
int nframes_;
float init_delay_;
int skip_num_;
float master_fps_;
int binning_;
bool color_;
string dump_img_;
Expand All @@ -133,7 +132,6 @@ namespace acquisition {
bool EXTERNAL_TRIGGER_;
bool SAVE_;
bool SAVE_BIN_;
bool MANUAL_TRIGGER_;
bool LIVE_;
bool CAM_DIRS_CREATED_;
bool GRID_VIEW_;
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>spinnaker_sdk_camera_driver</name>
<version>1.1.0</version>
<version>1.1.1</version>
<description>Point Grey (FLIR) Spinnaker based camera driver (Blackfly S etc.)</description>

<maintainer email="[email protected]">Vikrant Shah</maintainer>
Expand Down
61 changes: 24 additions & 37 deletions src/capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,6 @@ void acquisition::Capture::init_variables_register_to_ros() {
region_of_interest_set_ = false;
skip_num_ = 20;
init_delay_ = 1;
master_fps_ = 20.0;
binning_ = 1;
SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_ = 2000;
todays_date_ = todays_date();
Expand Down Expand Up @@ -126,7 +125,6 @@ void acquisition::Capture::init_variables_register_to_ros() {

// default flag values

MANUAL_TRIGGER_ = false;
CAM_DIRS_CREATED_ = false;

GRID_CREATED_ = false;
Expand Down Expand Up @@ -385,8 +383,9 @@ void acquisition::Capture::read_parameters() {
found = true;
}
ROS_ASSERT_MSG(found,"Specified master cam is not in the cam_ids list!");

}

if (nh_pvt_.getParam("utstamps", MASTER_TIMESTAMP_FOR_ALL_)){
MASTER_TIMESTAMP_FOR_ALL_ = !MASTER_TIMESTAMP_FOR_ALL_;
ROS_INFO(" Unique time stamps for each camera: %s",!MASTER_TIMESTAMP_FOR_ALL_?"true":"false");
Expand Down Expand Up @@ -462,15 +461,6 @@ void acquisition::Capture::read_parameters() {
}
} else ROS_WARN(" 'delay' Parameter not set, using default behavior: delay=%f",init_delay_);

if (nh_pvt_.getParam("fps", master_fps_)){
if (master_fps_>=0) ROS_INFO(" Master cam fps set to : %0.2f",master_fps_);
else {
master_fps_=20;
ROS_WARN(" Provided 'fps' is not valid, using default behavior, fps=%0.2f",master_fps_);
}
}
else ROS_WARN(" 'fps' Parameter not set, using default behavior: fps=%0.2f",master_fps_);

if (nh_pvt_.getParam("exposure_time", exposure_time_)){
if (exposure_time_ >0) ROS_INFO(" Exposure set to: %.1f",exposure_time_);
else ROS_INFO(" 'exposure_time'=%0.f, Setting autoexposure",exposure_time_);
Expand All @@ -489,7 +479,6 @@ void acquisition::Capture::read_parameters() {
else ROS_INFO(" 'target_grey_value'=%0.f, Setting AutoExposureTargetGreyValueAuto to Continuous/ auto",target_grey_value_);}
else ROS_WARN(" 'target_grey_value' Parameter not set, using default behavior: AutoExposureTargetGreyValueAuto to auto");


if (nh_pvt_.getParam("binning", binning_)){
if (binning_ >0) ROS_INFO(" Binning set to: %d",binning_);
else {
Expand All @@ -499,13 +488,13 @@ void acquisition::Capture::read_parameters() {
} else ROS_WARN(" 'binning' Parameter not set, using default behavior: Binning = %d",binning_);

if (nh_pvt_.getParam("soft_framerate", soft_framerate_)){
if (soft_framerate_ >0) {
SOFT_FRAME_RATE_CTRL_=true;
ROS_INFO(" Using Software rate control, rate set to: %d",soft_framerate_);
}
else ROS_INFO(" 'soft_framerate'=%d, software rate control set to off",soft_framerate_);
if (soft_framerate_ >0) {
SOFT_FRAME_RATE_CTRL_=true;
ROS_INFO(" Using Software rate control, rate set to: %d",soft_framerate_);
}
else ROS_INFO(" 'soft_framerate'=%d, software rate control set to off",soft_framerate_);
}
else ROS_WARN(" 'soft_framerate' Parameter not set, using default behavior: No Software Rate Control ");
else ROS_WARN(" 'soft_framerate' Parameter not set, using default behavior: No Software Rate Control ");

if (nh_pvt_.getParam("save", SAVE_))
ROS_INFO(" Saving images set to: %d",SAVE_);
Expand Down Expand Up @@ -837,6 +826,7 @@ void acquisition::Capture::save_mat_frames(int dump) {
create_cam_directories();

string timestamp;
mesg.name.clear();
for (unsigned int i = 0; i < numCameras_; i++) {

if (dump) {
Expand Down Expand Up @@ -879,7 +869,8 @@ void acquisition::Capture::export_to_ROS() {
else if (latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0){
double wait_time_start = ros::Time::now().toSec();
ROS_WARN("Difference in trigger count zero, latest_count = %d and prev_count = %d",latest_imu_trigger_count_,prev_imu_trigger_count_);
while(latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0){
while(latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0){

ros::Duration(0.0001).sleep();
}
ROS_INFO_STREAM("Time gap for sync messages: "<<ros::Time::now().toSec() - wait_time_start);
Expand Down Expand Up @@ -924,6 +915,7 @@ void acquisition::Capture::save_binary_frames(int dump) {
create_cam_directories();

string timestamp;
mesg.name.clear();
for (unsigned int i = 0; i < numCameras_; i++) {

if (dump) {
Expand Down Expand Up @@ -1065,20 +1057,17 @@ void acquisition::Capture::run_soft_trig() {
} else if( (key & 255)==81 ) { // LEFT ARROW
if (CAM_>0)
CAM_--;
} else if( (key & 255)==84 && MANUAL_TRIGGER_) { // t
cams[MASTER_CAM_].trigger();
get_mat_images();
} else if( (key & 255)==32 && !SAVE_) { // SPACE
ROS_INFO_STREAM("Saving frame...");
if (SAVE_BIN_)
save_binary_frames(0);
else{
save_mat_frames(0);
if (!EXPORT_TO_ROS_){
ROS_INFO_STREAM("Exporting frames to ROS...");
export_to_ROS();
}
else{
save_mat_frames(0);
if (!EXPORT_TO_ROS_){
ROS_INFO_STREAM("Exporting frames to ROS...");
export_to_ROS();
}
}
} else if( (key & 255)==27 ) { // ESC
ROS_INFO_STREAM("Terminating...");
cvDestroyAllWindows();
Expand All @@ -1091,12 +1080,11 @@ void acquisition::Capture::run_soft_trig() {
double disp_time_ = ros::Time::now().toSec() - t;

// Call update functions
if (!MANUAL_TRIGGER_) {
if (!EXTERNAL_TRIGGER_) {
cams[MASTER_CAM_].trigger();
}
get_mat_images();

if (!EXTERNAL_TRIGGER_) {
cams[MASTER_CAM_].trigger();
}
get_mat_images();

if (SAVE_) {
count++;
Expand All @@ -1107,7 +1095,7 @@ void acquisition::Capture::run_soft_trig() {
}

if (FIXED_NUM_FRAMES_) {
cout<<"Nframes "<< nframes_<<endl;
ROS_INFO_STREAM(" Recorded frames "<<count<<" / "<<nframes_);
if (count > nframes_) {
ROS_INFO_STREAM(nframes_ << " frames recorded. Terminating...");
cvDestroyAllWindows();
Expand All @@ -1133,8 +1121,7 @@ void acquisition::Capture::run_soft_trig() {

achieved_time_=ros::Time::now().toSec();

if (SOFT_FRAME_RATE_CTRL_) {ros_rate.sleep();}

if (!EXTERNAL_TRIGGER_ && SOFT_FRAME_RATE_CTRL_) {ros_rate.sleep();}
}
}
catch(const std::exception &e){
Expand Down

0 comments on commit 9c96330

Please sign in to comment.