Skip to content
Closed
Show file tree
Hide file tree
Changes from 1 commit
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
Next Next commit
Robot configs
  • Loading branch information
afr2903 committed Nov 3, 2023
commit 70555e7f394f33604e8e4fa96166e8e35eade7f2
69 changes: 69 additions & 0 deletions zed_wrapper/launch/PCtoLS.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
<!--
Launches point cloud to laser scan node: http://wiki.ros.org/pointcloud_to_laserscan
-->
<launch>
<remap from="/scan" to="/pc2ls"/>

<node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="point_cloud_to_laser" output="screen" respawn="true" >
<remap from="/cloud_in" to="/zed2/zed_node/point_cloud/ds_cloud_registered"/>
<param name="min_height" value="0.0"/>
<param name="max_height" value="1.0"/>
<param name="angle_min" value="-3.14/2"/>
<param name="angle_max" value="3.14/2"/>
<param name="angle_increment" value="3.14/360"/>
<param name="scan_time" value="1.0/30.0"/>
<param name="range_min" value="0.45"/>
<param name="range_max" value="4.0"/>
<!-- <param name="target_frame" value="none"/> -->
<param name="concurrency_level" value="1"/>
<param name="use_inf" value="true"/>
</node>
</launch>

<!--
Params of pointcloud_to_laserscan

~min_height (double, default: 0.0)

The minimum height to sample in the point cloud in meters.

~max_height (double, default: 1.0)

The maximum height to sample in the point cloud in meters.

~angle_min (double, default: -π/2)

The minimum scan angle in radians.

~angle_max (double, default: π/2)

The maximum scan angle in radians.

~angle_increment (double, default: π/360)

Resolution of laser scan in radians per ray.

~scan_time (double, default: 1.0/30.0)

The scan rate in seconds.

~range_min (double, default: 0.45)

The minimum ranges to return in meters.

~range_max (double, default: 4.0)

The maximum ranges to return in meters.

~target_frame (str, default: none)

If provided, transform the pointcloud into this frame before converting to a laser scan. Otherwise, laser scan will be generated in the same frame as the input point cloud.

~concurrency_level (int, default: 1)

Number of threads to use for processing pointclouds. If 0, automatically detect number of cores and use the equivalent number of threads. Input queue size for pointclouds is tied to this parameter. In nodelet form, number of threads is capped by the nodelet manager configuration.

~use_inf (boolean, default: true)

If disabled, report infinite range (no obstacle) as range_max + 1. Otherwise report infinite range as +inf. Associated with the inf_is_valid parameter for costmap_2d obstacle layers.
-->
58 changes: 58 additions & 0 deletions zed_wrapper/launch/zed2_robot.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
<?xml version="1.0"?>
<!--
Copyright (c) 2023, STEREOLABS.

All rights reserved.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<launch>
<arg name="svo_file" default="" /> <!-- <arg name="svo_file" default="path/to/svo/file.svo"> -->
<arg name="stream" default="" /> <!-- <arg name="stream" default="<ip_address>:<port>"> -->

<arg name="node_name" default="zed_node" />
<arg name="camera_model" default="zed2" />
<arg name="publish_urdf" default="true" />

<arg name="camera_name" default="zed2" />

<arg name="base_frame" default="Cam1_ry_rz" /> <!-- <arg name="base_frame" default="Cam1_ry_rz" /> -->

<arg name="cam_pos_x" default="0.0" /> <!-- Position respect to base frame (i.e. "base_link) -->
<arg name="cam_pos_y" default="0.0" /> <!-- Position respect to base frame (i.e. "base_link) -->
<arg name="cam_pos_z" default="0.0" /> <!-- Position respect to base frame (i.e. "base_link) -->
<arg name="cam_roll" default="0.0" /> <!-- Orientation respect to base frame (i.e. "base_link) -->
<arg name="cam_pitch" default="0.0" /> <!-- Orientation respect to base frame (i.e. "base_link) -->
<arg name="cam_yaw" default="0.0" /> <!-- Orientation respect to base frame (i.e. "base_link) -->

<group ns="$(arg camera_name)">
<include file="$(find zed_wrapper)/launch/include/zed_camera.launch.xml">
<arg name="camera_name" value="$(arg camera_name)" />
<arg name="svo_file" value="$(arg svo_file)" />
<arg name="stream" value="$(arg stream)" />
<arg name="node_name" value="$(arg node_name)" />
<arg name="camera_model" value="$(arg camera_model)" />
<arg name="base_frame" value="$(arg base_frame)" />
<arg name="publish_urdf" value="$(arg publish_urdf)" />
<arg name="cam_pos_x" value="$(arg cam_pos_x)" />
<arg name="cam_pos_y" value="$(arg cam_pos_y)" />
<arg name="cam_pos_z" value="$(arg cam_pos_z)" />
<arg name="cam_roll" value="$(arg cam_roll)" />
<arg name="cam_pitch" value="$(arg cam_pitch)" />
<arg name="cam_yaw" value="$(arg cam_yaw)" />
</include>
</group>

<include file="$(find pc_processing)/launch/pc_downsample.launch"/>

</launch>
36 changes: 18 additions & 18 deletions zed_wrapper/params/common.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,11 @@ general:
base_frame: 'base_link' # must be equal to the frame_id used in the URDF file
sdk_verbose: 1 # Set verbose level of the ZED SDK
svo_compression: 2 # `0`: LOSSLESS, `1`: AVCHD, `2`: HEVC
self_calib: true # enable/disable self calibration at starting
camera_flip: 'AUTO' # camera flip mode: 'OFF', 'ON', 'AUTO'
self_calib: false # enable/disable self calibration at starting
camera_flip: 'OFF' # camera flip mode: 'OFF', 'ON', 'AUTO'
pub_resolution: 'CUSTOM' # The resolution used for output. 'NATIVE' to use the same `general.grab_resolution` - `CUSTOM` to apply the `general.pub_downscale_factor` downscale factory to reduce bandwidth in transmission
pub_downscale_factor: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM'
pub_frame_rate: 15.0 # frequency of publishing of video and depth data (see SDK API "InitParameters::grab_compute_capping_fps")
pub_frame_rate: 10.0 # frequency of publishing of video and depth data (see SDK API "InitParameters::grab_compute_capping_fps")
svo_realtime: true # if true the input SVO will be played trying to respect the original framerate eventually skipping frames, otherwise every frame will be processed respecting the `pub_frame_rate` setting
region_of_interest: '[]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
#region_of_interest: '[[0.25,0.33],[0.75,0.33],[0.75,0.5],[0.5,0.75],[0.25,0.5]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
Expand All @@ -40,25 +40,25 @@ general:
#video:

depth:
depth_mode: 'ULTRA' # 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL'
depth_mode: 'NEURAL' # 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL'
depth_stabilization: 1 # [0-100] - 0: Disabled
openni_depth_mode: false # 'false': 32bit float meter units, 'true': 16bit uchar millimeter units

pos_tracking:
pos_tracking_enabled: true # True to enable positional tracking from start
pos_tracking_enabled: false # True to enable positional tracking from start
pos_tracking_mode: 'STANDARD' # Matches the ZED SDK setting: 'QUALITY', 'STANDARD' -> Use 'QUALITY' with 'ULTRA' depth mode for improved outdoors performance
set_gravity_as_origin: true # If 'true' align the positional tracking world to imu gravity measurement. Keep the yaw from the user initial pose.
imu_fusion: true # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
publish_tf: true # publish `odom -> base_link` TF
publish_map_tf: true # publish `map -> odom` TF
set_gravity_as_origin: false # If 'true' align the positional tracking world to imu gravity measurement. Keep the yaw from the user initial pose.
imu_fusion: false # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
publish_tf: false # publish `odom -> base_link` TF
publish_map_tf: false # publish `map -> odom` TF
map_frame: 'map' # main frame
odometry_frame: 'odom' # odometry frame
area_memory_db_path: '' # file loaded when the node starts to restore the "known visual features" map.
save_area_memory_db_on_exit: false # save the "known visual features" map when the node is correctly closed to the path indicated by `area_memory_db_path`
area_memory: true # Enable to detect loop closure
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]
init_odom_with_first_valid_pose: true # Enable to initialize the odometry with the first valid pose
init_odom_with_first_valid_pose: false # Enable to initialize the odometry with the first valid pose
path_pub_rate: 2.0 # Camera trajectory publishing frequency
path_max_count: -1 # use '-1' for unlimited path size
two_d_mode: false # Force navigation on a plane. If true the Z value will be fixed to "fixed_z_value", roll and pitch to zero
Expand All @@ -84,11 +84,11 @@ object_detection:
max_range: 15. # Maximum detection range
allow_reduced_precision_inference: true # Allow inference to run at a lower precision to improve runtime and memory usage
prediction_timeout: 0.5 # During this time [sec], the object will have OK state even if it is not detected. Set this parameter to 0 to disable SDK predictions
object_tracking_enabled: true # Enable/disable the tracking of the detected objects
mc_people: true # Enable/disable the detection of persons for 'MULTI_CLASS_BOX_X' models
mc_vehicle: true # Enable/disable the detection of vehicles for 'MULTI_CLASS_BOX_X' models
mc_bag: true # Enable/disable the detection of bags for 'MULTI_CLASS_BOX_X' models
mc_animal: true # Enable/disable the detection of animals for 'MULTI_CLASS_BOX_X' models
mc_electronics: true # Enable/disable the detection of electronic devices for 'MULTI_CLASS_BOX_X' models
mc_fruit_vegetable: true # Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_BOX_X' models
mc_sport: true # Enable/disable the detection of sport-related objects for 'MULTI_CLASS_BOX_X' models
object_tracking_enabled: false # Enable/disable the tracking of the detected objects
mc_people: false # Enable/disable the detection of persons for 'MULTI_CLASS_BOX_X' models
mc_vehicle: false # Enable/disable the detection of vehicles for 'MULTI_CLASS_BOX_X' models
mc_bag: false # Enable/disable the detection of bags for 'MULTI_CLASS_BOX_X' models
mc_animal: false # Enable/disable the detection of animals for 'MULTI_CLASS_BOX_X' models
mc_electronics: false # Enable/disable the detection of electronic devices for 'MULTI_CLASS_BOX_X' models
mc_fruit_vegetable: false # Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_BOX_X' models
mc_sport: false # Enable/disable the detection of sport-related objects for 'MULTI_CLASS_BOX_X' models
4 changes: 2 additions & 2 deletions zed_wrapper/params/zed2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@

general:
camera_model: 'zed2'
grab_resolution: 'HD720' # 'HD2K', 'HD1080', 'HD720', 'VGA', 'AUTO'
grab_frame_rate: 30 # Frequency of frame grabbing for internal SDK operations
grab_resolution: 'HD1080' # 'HD2K', 'HD1080', 'HD720', 'VGA', 'AUTO'
grab_frame_rate: 25 # Frequency of frame grabbing for internal SDK operations

depth:
min_depth: 0.3 # Min: 0.2, Max: 3.0 - Default 0.7 - Note: reducing this value wil require more computational power and GPU memory
Expand Down