Skip to content
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
4 changes: 4 additions & 0 deletions launch/zed_camera.launch
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<!-- Publish urdf zed -->
<arg name="publish_urdf" default="true" />

<!-- to flip or not to flip -->
<arg name="camera_flip" default="true" />
<arg name="rgb_topic" default="rgb/image_rect_color" />
<arg name="rgb_info_topic" default="rgb/camera_info" />
<arg name="depth_topic" default="depth/depth_registered" />
Expand All @@ -61,6 +63,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<!-- publish pose frame -->
<param name="publish_tf" value="$(arg publish_tf)" />

<!-- flip camera -->
<param name="camera_flip" value="$(arg camera_flip)" />
<!-- Configuration frame camera -->
<param name="pose_frame" value="$(arg pose_frame)" />
<param name="odometry_frame" value="$(arg odometry_frame)" />
Expand Down
1 change: 1 addition & 0 deletions src/nodelet/include/zed_wrapper_nodelet.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -284,6 +284,7 @@ class ZEDWrapperNodelet : public nodelet::Nodelet {
boost::shared_ptr<tf2_ros::Buffer> tfBuffer;
boost::shared_ptr<tf2_ros::TransformListener> tfListener;
bool publishTf;
bool cameraFlip;

// Launch file parameters
int resolution;
Expand Down
6 changes: 5 additions & 1 deletion src/nodelet/src/zed_wrapper_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,8 @@ void ZEDWrapperNodelet::onInit() {
// Publish odometry tf
nhNs.param<bool>("publish_tf", publishTf, true);

nhNs.param<bool>("camera_flip", cameraFlip, false);

if (serial_number > 0)
NODELET_INFO_STREAM("SN : " << serial_number);

Expand All @@ -152,6 +154,7 @@ void ZEDWrapperNodelet::onInit() {
// Status of map TF
NODELET_INFO_STREAM("Publish " << mapFrameId << " ["
<< (publishTf ? "TRUE" : "FALSE") << "]");
NODELET_INFO_STREAM("Camera Flip [" << (cameraFlip ? "TRUE" : "FALSE") << "]");

// Status of odometry TF
// NODELET_INFO_STREAM("Publish " << odometry_frame_id << " [" << (publish_tf
Expand Down Expand Up @@ -338,7 +341,8 @@ void ZEDWrapperNodelet::onInit() {
param.sdk_verbose = verbose;
param.sdk_gpu_id = gpuId;
param.depth_stabilization = depthStabilization;

param.camera_image_flip = cameraFlip;

sl::ERROR_CODE err = sl::ERROR_CODE_CAMERA_NOT_DETECTED;
while (err != sl::SUCCESS) {
err = zed.open(param);
Expand Down