From 492e285347d3fa953ae5b2a5723bdb44c1722812 Mon Sep 17 00:00:00 2001 From: Faraz Khan Date: Tue, 3 Jul 2018 11:09:36 -0700 Subject: [PATCH 1/2] - Add camera flip argument --- launch/zed_camera.launch | 6 ++++++ src/zed_wrapper_nodelet.cpp | 4 ++++ 2 files changed, 10 insertions(+) diff --git a/launch/zed_camera.launch b/launch/zed_camera.launch index 386257d0..740cdb46 100644 --- a/launch/zed_camera.launch +++ b/launch/zed_camera.launch @@ -33,12 +33,18 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + + + + diff --git a/src/zed_wrapper_nodelet.cpp b/src/zed_wrapper_nodelet.cpp index 2120882e..c80422ae 100644 --- a/src/zed_wrapper_nodelet.cpp +++ b/src/zed_wrapper_nodelet.cpp @@ -124,6 +124,7 @@ namespace zed_wrapper { boost::shared_ptr tfBuffer; boost::shared_ptr tf_listener; bool publish_tf; + bool camera_flip; // Launch file parameters int resolution; @@ -809,6 +810,7 @@ namespace zed_wrapper { // Publish odometry tf nh_ns.param("publish_tf", publish_tf, true); + nh_ns.param("camera_flip", camera_flip, false); if (serial_number > 0) ROS_INFO_STREAM("SN : " << serial_number); @@ -820,6 +822,7 @@ namespace zed_wrapper { ROS_INFO_STREAM("depth_frame: " << depth_frame_id); // Status of odometry TF ROS_INFO_STREAM("Publish " << odometry_frame_id << " [" << (publish_tf ? "TRUE" : "FALSE") << "]"); + ROS_INFO_STREAM("Camera Flip [" << (camera_flip ? "TRUE" : "FALSE") << "]"); std::string img_topic = "image_rect_color"; std::string img_raw_topic = "image_raw_color"; @@ -920,6 +923,7 @@ namespace zed_wrapper { param.sdk_verbose = true; param.sdk_gpu_id = gpu_id; param.depth_stabilization = depth_stabilization; + param.camera_image_flip = camera_flip; sl::ERROR_CODE err = sl::ERROR_CODE_CAMERA_NOT_DETECTED; while (err != sl::SUCCESS) { From e05c7d3c2c129330c0f21f5dcc3e35bfd0f593e6 Mon Sep 17 00:00:00 2001 From: Faraz Khan Date: Thu, 26 Jul 2018 20:56:46 -0700 Subject: [PATCH 2/2] - Make it work with the new ROS package --- src/nodelet/src/zed_wrapper_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/nodelet/src/zed_wrapper_nodelet.cpp b/src/nodelet/src/zed_wrapper_nodelet.cpp index d4cb0f8d..8c02b21f 100644 --- a/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -341,7 +341,7 @@ void ZEDWrapperNodelet::onInit() { param.sdk_verbose = verbose; param.sdk_gpu_id = gpuId; param.depth_stabilization = depthStabilization; - param.camera_flip = cameraFlip; + param.camera_image_flip = cameraFlip; sl::ERROR_CODE err = sl::ERROR_CODE_CAMERA_NOT_DETECTED; while (err != sl::SUCCESS) {