|
| 1 | +# include/vlp16.launch.py |
| 2 | +pointcloud_to_laserscan_node: |
| 3 | + ros__parameters: |
| 4 | + target_frame: velodyne |
| 5 | + transform_tolerance: 0.01 |
| 6 | + min_height: -0.30 # origin is the sensor |
| 7 | + max_height: 1.4 # origin is the sensor |
| 8 | + angle_min: -2.57 # -M_PI/2 - 1.0 (angle clipping) |
| 9 | + angle_max: 1.57 # M_PI/2 |
| 10 | + angle_increment: 0.00436 # M_PI/360/2 |
| 11 | + scan_time: 0.1 |
| 12 | + range_min: 0.2 |
| 13 | + range_max: 50.0 |
| 14 | + use_inf: True |
| 15 | + inf_epsilon: 1.0 |
| 16 | + # Concurrency level affects number of pointclouds queued for |
| 17 | + # processing and number of threads used |
| 18 | + # 0 : Detect number of cores |
| 19 | + # 1 : Single threaded |
| 20 | + # 2->inf : Parallelism level |
| 21 | + concurrency_level: 0 |
| 22 | + |
| 23 | + |
| 24 | +# crop box size is increased to ignore pointcloud following the user |
| 25 | +filter_crop_box_node: |
| 26 | + ros__parameters: |
| 27 | + min_x: -10.0 |
| 28 | + min_y: -1.5 |
| 29 | + min_z: 0.0 |
| 30 | + max_x: 0.2 |
| 31 | + max_y: 1.5 |
| 32 | + max_z: 2.0 |
| 33 | + keep_organized: False |
| 34 | + negative: True |
| 35 | + input_frame: base_link |
| 36 | + output_frame: velodyne |
| 37 | +#------ vlp.16.launch.xml |
| 38 | + |
| 39 | +cabot: |
| 40 | + cabot_handle_v2_node: |
| 41 | + ros__parameters: |
| 42 | + no_vibration: false |
| 43 | + buttons: ['NEED_TO_BE_CONFIGURED'] |
| 44 | + |
| 45 | + cabot_serial: |
| 46 | + ros__parameters: |
| 47 | + port: NEED_TO_BE_CONFIGURED |
| 48 | + baud: 115200 |
| 49 | + calibration_params: [0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0] |
| 50 | + touch_params: [128,48,24] # NEED_TO_BE_CONFIGURED |
| 51 | + |
| 52 | + serial_esp32_wifi_scanner: |
| 53 | + ros__parameters: |
| 54 | + port: /dev/ttyESP32 |
| 55 | + baud: 115200 |
| 56 | + verbose: False |
| 57 | + |
| 58 | + odriver_adapter_node: |
| 59 | + ros__parameters: |
| 60 | + encoder_topic: /cabot/motorStatus |
| 61 | + odom_topic: /cabot/odom_raw |
| 62 | + motor_topic: /cabot/motorTarget |
| 63 | + cmd_vel_topic: /cabot/cmd_vel |
| 64 | + pause_control_topic: /cabot/pause_control |
| 65 | + max_acc: 1.2 |
| 66 | + max_dec: -1.2 |
| 67 | + target_rate: 20 |
| 68 | + bias: 1.0 # NEED_TO_BE_CONFIGURED |
| 69 | + gain_omega: 1.0 # NEED_TO_BE_CONFIGURED |
| 70 | + gain_omega_i: 0.0 # NEED_TO_BE_CONFIGURED |
| 71 | + |
| 72 | + odriver_node: |
| 73 | + ros__parameters: |
| 74 | + wheel_diameter: 0.073 # NEED_TO_BE_CONFIGURED |
| 75 | + count_per_round: 16384 # NEED_TO_BE_CONFIGURED |
| 76 | + left_is_1: false # NEED_TO_BE_CONFIGURED |
| 77 | + is_clockwise: true # NEED_TO_BE_CONFIGURED |
| 78 | + gain_left: 1.0 # NEED_TO_BE_CONFIGURED |
| 79 | + gain_right: 1.0 # NEED_TO_BE_CONFIGURED |
| 80 | + port: /dev/ttyODRIVE |
| 81 | + vel_gain: 1.0 # NEED_TO_BE_CONFIGURED |
| 82 | + vel_integrator_gain: 10.0 # NEED_TO_BE_CONFIGURED |
| 83 | + motor_bandwidth: 200 # NEED_TO_BE_CONFIGURED |
| 84 | + encoder_bandwidth: 200 # NEED_TO_BE_CONFIGURED |
| 85 | + |
0 commit comments