Skip to content
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

added static camera position config option #122

Merged
merged 1 commit into from
Nov 30, 2022
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
Original file line number Diff line number Diff line change
Expand Up @@ -343,6 +343,7 @@ class ZedCamera : public rclcpp::Node
double mPathPubRate = 2.0;
double mTfOffset = 0.05;
double mPosTrackDepthMinRange = 0.0;
bool mSetAsStatic = false;
bool mSetGravityAsOrigin = false;
int mPathMaxCount = -1;
bool mPublishPoseCov = true;
Expand Down
5 changes: 5 additions & 0 deletions zed_components/src/zed_camera/src/zed_camera_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1048,6 +1048,10 @@ void ZedCamera::getPosTrackingParams()
getParam(
"pos_tracking.area_memory_db_path", mAreaMemoryDbPath, mAreaMemoryDbPath,
" * Area Memory DB: ");
getParam("pos_tracking.set_as_static", mSetAsStatic, mSetAsStatic);
RCLCPP_INFO_STREAM(
get_logger(),
" * Camera is static: " << (mSetAsStatic ? "TRUE" : "FALSE"));
getParam("pos_tracking.set_gravity_as_origin", mSetGravityAsOrigin, mSetGravityAsOrigin);
RCLCPP_INFO_STREAM(
get_logger(),
Expand Down Expand Up @@ -2771,6 +2775,7 @@ bool ZedCamera::startPosTracking()
trackParams.initial_world_transform = mInitialPoseSl;
trackParams.set_floor_as_origin = mFloorAlignment;
trackParams.depth_min_range = mPosTrackDepthMinRange;
trackParams.set_as_static = mSetAsStatic;
trackParams.set_gravity_as_origin = mSetGravityAsOrigin;

sl::ERROR_CODE err = mZed.enablePositionalTracking(trackParams);
Expand Down
1 change: 1 addition & 0 deletions zed_wrapper/config/common.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@
area_memory_db_path: ""
area_memory: true # Enable to detect loop closure
depth_min_range: 0.0 # Set this value for removing fixed zones of the robot in the FoV of the camerafrom the visual odometry evaluation
set_as_static: false # If 'true' the camera will be static and not move in the environment
set_gravity_as_origin: false # If 'true' align the positional tracking world to imu gravity measurement. Keep the yaw from the user initial pose.
floor_alignment: false # Enable to automatically calculate camera/floor offset
initial_base_pose: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Initial position of the `base_frame` -> [X, Y, Z, R, P, Y]
Expand Down