-
Notifications
You must be signed in to change notification settings - Fork 76
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
Adding device selection support #9
Changes from 4 commits
0385fb1
1486f4e
d1da438
3adde9d
311cb52
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,6 +1,7 @@ | ||
<launch> | ||
<arg name="config_file_location" default="$(find zed_cpu_ros)/config/SN1267.conf"/> | ||
<arg name="camera_namespace" default="camera"/> | ||
<arg name="device" default="0"/> | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. change to device_id every where There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Done in 311cb52 :) |
||
|
||
<node pkg="zed_cpu_ros" type="zed_cpu_ros" name="zed_cpu_ros_node" output="screen" ns="$(arg camera_namespace)" required="true"> | ||
<param name="resolution" value="2"/> | ||
|
@@ -10,6 +11,7 @@ | |
<param name="left_frame_id" value="left_frame"/> | ||
<param name="right_frame_id" value="right_frame"/> | ||
<param name="load_zed_config" value="true"/> | ||
<param name="device" value="$(arg device)"/> | ||
</node> | ||
|
||
<node pkg="tf" type="static_transform_publisher" name="static_tf_1" args="0.25 0 0.4 0 0 0 1 base_link left_frame 30"/> | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -31,9 +31,10 @@ class StereoCamera | |
* @param[in] resolution The resolution | ||
* @param[in] frame_rate The frame rate | ||
*/ | ||
StereoCamera(int resolution, double frame_rate): frame_rate_(30.0) { | ||
StereoCamera(int device, int resolution, double frame_rate) | ||
: frame_rate_(30.0) { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. can you make this on the same line? Thanks There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Done in 311cb52 :) |
||
|
||
camera_ = new cv::VideoCapture(0); | ||
camera_ = new cv::VideoCapture(device); | ||
cv::Mat raw; | ||
cv::Mat left_image; | ||
cv::Mat right_image; | ||
|
@@ -135,9 +136,10 @@ class ZedCameraROS { | |
private_nh.param("right_frame_id", right_frame_id_, std::string("right_camera")); | ||
private_nh.param("show_image", show_image_, false); | ||
private_nh.param("load_zed_config", load_zed_config_, true); | ||
private_nh.param("device", device_, 0); | ||
|
||
ROS_INFO("Try to initialize the camera"); | ||
StereoCamera zed(resolution_, frame_rate_); | ||
StereoCamera zed(device_, resolution_, frame_rate_); | ||
ROS_INFO("Initialized the camera"); | ||
|
||
// setup publisher stuff | ||
|
@@ -381,7 +383,7 @@ class ZedCameraROS { | |
} | ||
|
||
private: | ||
int resolution_; | ||
int device_, resolution_; | ||
double frame_rate_; | ||
bool show_image_, load_zed_config_; | ||
double width_, height_; | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
fix the format?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I was using auto-formatting tool (Atom Beautify) which changed indentation in several files. I just reverse patched those changes.