diff --git a/.github/dependabot.yml b/.github/dependabot.yml index b38df29f4..425d058e7 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -1,6 +1,9 @@ +--- + version: 2 + updates: - - package-ecosystem: "pip" - directory: "/" + - package-ecosystem: pip + directory: / schedule: - interval: "daily" + interval: daily diff --git a/.github/workflows/mdbook-deploy.yml b/.github/workflows/mdbook-deploy.yml index 797a04e99..0ee59b7b5 100644 --- a/.github/workflows/mdbook-deploy.yml +++ b/.github/workflows/mdbook-deploy.yml @@ -2,6 +2,7 @@ name: mdbook-deploy +# yamllint disable-line rule:truthy on: push: branches: diff --git a/.github/workflows/mdbook.yml b/.github/workflows/mdbook.yml index 7ba396c2f..7a553565b 100644 --- a/.github/workflows/mdbook.yml +++ b/.github/workflows/mdbook.yml @@ -2,8 +2,9 @@ name: mdbook +# yamllint disable-line rule:truthy on: - pull_request: + pull_request: ~ jobs: build: diff --git a/.github/workflows/node_bl.yml b/.github/workflows/node_bl.yml index f280ca0a8..279198a11 100644 --- a/.github/workflows/node_bl.yml +++ b/.github/workflows/node_bl.yml @@ -1,7 +1,10 @@ +--- + name: Build node_bl # node_bl job triggers disabled for now while bootloader is under rework # on: [pull_request, push, workflow_dispatch] +# yamllint disable-line rule:truthy on: workflow_dispatch jobs: @@ -41,13 +44,13 @@ jobs: - name: Build firmware run: . .venv/bin/activate && make dbw/node_bl - - name: 'Upload CAN network' + - name: Upload CAN network uses: actions/upload-artifact@v3 with: name: can-dbc path: build/can/igvc_can.dbc - - name: 'Upload firmware binaries' + - name: Upload firmware binaries uses: actions/upload-artifact@v3 with: name: node_bl-bin diff --git a/.github/workflows/node_fw.yml b/.github/workflows/node_fw.yml index ac12f8566..de443f313 100644 --- a/.github/workflows/node_fw.yml +++ b/.github/workflows/node_fw.yml @@ -1,6 +1,12 @@ +--- + name: Build node_fw -on: [pull_request, push, workflow_dispatch] +# yamllint disable-line rule:truthy +on: + - pull_request + - push + - workflow_dispatch jobs: pre_job: @@ -17,7 +23,7 @@ jobs: needs: pre_job if: ${{ needs.pre_job.outputs.should_skip != 'true' }} - runs-on: ubuntu-22.04 + runs-on: ubuntu-latest steps: - uses: actions/checkout@v3 diff --git a/.github/workflows/pre-commit.yml b/.github/workflows/pre-commit.yml index 4c0e33c11..be69fea17 100644 --- a/.github/workflows/pre-commit.yml +++ b/.github/workflows/pre-commit.yml @@ -2,9 +2,10 @@ name: pre-commit +# yamllint disable-line rule:truthy on: - pull_request: - push: + pull_request: ~ + push: ~ jobs: pre-commit: diff --git a/.github/workflows/sync-dev.yml b/.github/workflows/sync-dev.yml index ef35410f8..b1e3a5295 100644 --- a/.github/workflows/sync-dev.yml +++ b/.github/workflows/sync-dev.yml @@ -1,47 +1,53 @@ +--- + name: Sync `master` to `dev` +# yamllint disable-line rule:truthy on: push: branches: - - master + - master jobs: make-sync-pr: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 - - name: Create source branch - run: | - git config --global push.autoSetupRemote true - git checkout -b 'bot-branches/sync-master-dev-${{ github.sha }}' - git push + - uses: actions/checkout@v3 + - name: Create source branch + run: | + git config --global push.autoSetupRemote true + git checkout -b 'bot-branches/sync-master-dev-${{ github.sha }}' + git push - - name: Make PR - id: make-pr - uses: repo-sync/pull-request@v2 - with: - source_branch: 'bot-branches/sync-master-dev-${{ github.sha }}' - destination_branch: dev - github_token: ${{ secrets.BOT_PAT_SELFDRIVE }} - pr_title: '[SYNC-FIX] Merge out-of-sync changes from \`master\` into \`dev\`:grey_exclamation:' - pr_body: | - Hello! This PR has been automatically generated because you need to merge out-of-sync changes from \`master\` into \`dev\`. + - name: Make PR + id: make-pr + uses: repo-sync/pull-request@v2 + with: + source_branch: bot-branches/sync-master-dev-${{ github.sha }} + destination_branch: dev + github_token: ${{ secrets.BOT_PAT_SELFDRIVE }} + pr_title: > + '[SYNC-FIX] Merge out-of-sync changes from \`master\` into + \`dev\`:grey_exclamation:' + pr_body: > + Hello! This PR has been automatically generated because you need to + merge out-of-sync changes from \`master\` into \`dev\`. - **I will try to merge this PR on my own!** - pr_label: 'autosync,URGENT' - pr_allow_empty: true + **I will try to merge this PR on my own!** + pr_label: autosync,URGENT + pr_allow_empty: true - - name: Set automerge - if: ${{ steps.make-pr.outputs.pr_number != '' }} - uses: peter-evans/enable-pull-request-automerge@v2 - with: - token: ${{ secrets.BOT_PAT_SELFDRIVE }} - pull-request-number: ${{ steps.make-pr.outputs.pr_number }} - merge-method: merge + - name: Set automerge + if: ${{ steps.make-pr.outputs.pr_number != '' }} + uses: peter-evans/enable-pull-request-automerge@v2 + with: + token: ${{ secrets.BOT_PAT_SELFDRIVE }} + pull-request-number: ${{ steps.make-pr.outputs.pr_number }} + merge-method: merge - - name: Approve PR - if: ${{ steps.make-pr.outputs.pr_number != '' }} - uses: hmarr/auto-approve-action@v2 - with: - github-token: ${{ secrets.GITHUB_TOKEN }} # approve as GH Actions - pull-request-number: ${{ steps.make-pr.outputs.pr_number }} + - name: Approve PR + if: ${{ steps.make-pr.outputs.pr_number != '' }} + uses: hmarr/auto-approve-action@v2 + with: + github-token: ${{ secrets.GITHUB_TOKEN }} # approve as GH Actions + pull-request-number: ${{ steps.make-pr.outputs.pr_number }} diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 032e034a7..18c9e86a2 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -25,7 +25,9 @@ repos: rev: 0.7.17 hooks: - id: mdformat - args: [--wrap, '72'] + args: + - --wrap + - '72' exclude: LICENSE\.md additional_dependencies: - mdformat-gfm @@ -34,3 +36,13 @@ repos: rev: v0.1.1 hooks: - id: ruff + + - repo: https://github.com/lyz-code/yamlfix/ + rev: 1.13.0 + hooks: + - id: yamlfix + + - repo: https://github.com/adrienverge/yamllint + rev: v1.32.0 + hooks: + - id: yamllint diff --git a/.yamllint.yml b/.yamllint.yml new file mode 100644 index 000000000..f7f640d76 --- /dev/null +++ b/.yamllint.yml @@ -0,0 +1,7 @@ +--- + +extends: default + +ignore-from-file: + - .gitignore + - common/.gitignore diff --git a/can/can.yml b/can/can.yml index d54a068a8..7ae1a3355 100644 --- a/can/can.yml +++ b/can/can.yml @@ -3,9 +3,9 @@ bitrate: 500000 message_templates: -- DBWNodeInfo: - cycletime: 1000 - signals: + - DBWNodeInfo: + cycletime: 1000 + signals: - gitHash: description: Githash of the currently-running firmware. width: 32 @@ -16,99 +16,101 @@ message_templates: description: EEPROM identity. width: 6 -- DBWNodeStatus: - cycletime: 100 - - signals: - - sysStatus: - description: Status of the node. - enumerated_values: - - UNDEF - - INIT - - IDLE - - ACTIVE - - LOST_CAN - - BAD - - ESTOP - - requestedSysStatus: - description: Requested node status. - enumerated_values: - - UNDEF - - INIT - - IDLE - - ACTIVE - - LOST_CAN - - BAD - - ESTOP - - temperature: - description: Core temperature in Celsius - width: 7 - offset: 31 - - counter: - description: Counter for fun. - width: 8 - - resetReason: - description: Reset reason. - enumerated_values: - - POWERON - - SW_RESET - - WATCHDOG_RESET - - UNKNOWN - - esp32ResetReasonCode: - description: ESP32 reset reason code (enum RESET_REASON) - width: 5 - -- DBWVelocityCommand: - cycletime: 10 - - signals: - - brakePercent: - description: Brake percentage. - # mimumum: 0.0 - # maximum: 100.0 - unit: percent - width: 10 - scale: 0.1 - - throttlePercent: - description: Throttle percentage. - # minimum: 0.0 - # maximum: 100.0 - unit: percent - width: 10 - scale: 0.1 - -- EncoderData: - cycletime: 10 - signals: + - DBWNodeStatus: + cycletime: 100 + + signals: + - sysStatus: + description: Status of the node. + enumerated_values: + - UNDEF + - INIT + - IDLE + - ACTIVE + - LOST_CAN + - BAD + - ESTOP + - requestedSysStatus: + description: Requested node status. + enumerated_values: + - UNDEF + - INIT + - IDLE + - ACTIVE + - LOST_CAN + - BAD + - ESTOP + - temperature: + description: Core temperature in Celsius + width: 7 + offset: 31 + - counter: + description: Counter for fun. + width: 8 + - resetReason: + description: Reset reason. + enumerated_values: + - POWERON + - SW_RESET + - WATCHDOG_RESET + - UNKNOWN + - esp32ResetReasonCode: + description: ESP32 reset reason code (enum RESET_REASON) + width: 5 + + - DBWVelocityCommand: + cycletime: 10 + + signals: + - brakePercent: + description: Brake percentage. + # mimumum: 0.0 + # maximum: 100.0 + unit: percent + width: 10 + scale: 0.1 + - throttlePercent: + description: Throttle percentage. + # minimum: 0.0 + # maximum: 100.0 + unit: percent + width: 10 + scale: 0.1 + + - EncoderData: + cycletime: 10 + signals: - encoderLeft: - description: Left encoder pulses (continuous, bidirectional, and overflowing). + description: > + Left encoder pulses (continuous, bidirectional, and overflowing). width: 16 - encoderRight: - description: Right encoder pulses (continuous, bidirectional, and overflowing). + description: > + Right encoder pulses (continuous, bidirectional, and overflowing). width: 16 -- PIDGains: - signals: - - gainKp: - description: Kp gain. - width: 16 - scale: 0.001 + - PIDGains: + signals: + - gainKp: + description: Kp gain. + width: 16 + scale: 0.001 - - gainKi: - description: Ki gain. - width: 16 - scale: 0.001 + - gainKi: + description: Ki gain. + width: 16 + scale: 0.001 - - gainKd: - description: Kd gain. - width: 17 - twos_complement: true - scale: 0.001 + - gainKd: + description: Kd gain. + width: 17 + twos_complement: true + scale: 0.001 -- UpdateControl: - cycletime: 20 + - UpdateControl: + cycletime: 20 - signals: + signals: - updateSizeBytes: description: Total update binary size in bytes. width: 24 @@ -116,721 +118,718 @@ message_templates: description: Current isotp 4095-byte chunk. width: 12 -- BlStatus: - cycletime: 20 + - BlStatus: + cycletime: 20 - signals: + signals: - state: enumerated_values: - - AWAIT_TRIGGER - - RECV_CHUNK - - CHECK_DESC - - COMMIT_CHUNK - - FINALIZE - - REBOOT_FW - - FAULT - - RESET + - AWAIT_TRIGGER + - RECV_CHUNK + - CHECK_DESC + - COMMIT_CHUNK + - FINALIZE + - REBOOT_FW + - FAULT + - RESET nodes: -- BLINK: - rx: - - DBW_ESTOP - - UPD_UpdateControl_BLINK # bootloader - messages: - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD0 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE0 - -- BLINKBL: - rx: - - UPD_IsoTpTx_BLINK - - UPD_UpdateControl_BLINK - messages: - - IsoTpTx: - id: 0x501 - - Status: - from_template: BlStatus - id: 0x502 - -- BRAKE: - rx: - - CTRL_VelocityCommand - - DBW_ESTOP - - DBW_VelocityCommand - - SUP_Authorization - - UPD_UpdateControl_BRAKE # bootloader - messages: - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD2 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE2 - - - BrakeData: - id: 0x11 - cycletime: 100 - - signals: - - dutyCycle: - description: Brake duty cycle. - width: 10 - - - percent: - description: Percentage commanded. - # minimum: 0.0 - # maximum: 100.0 - width: 10 - unit: percent - scale: 0.1 -- BRAKEBL: - rx: - - UPD_IsoTpTx_BRAKE - - UPD_UpdateControl_BRAKE - messages: - - IsoTpTx: - id: 0x503 - - Status: - from_template: BlStatus - id: 0x504 - -- CTRL: - rx: - - DBW_ESTOP - - DBW_SetVelocityGains - - DBW_RawVelocityCommand - - DBW_VelocityCommand - - UPD_UpdateControl_CTRL # bootloader - messages: - - Alarms: - id: 0x22 - cycletime: 10 - - signals: - - alarmsRaised: - description: Alarms raised - width: 1 - - speedAlarm: - description: Speed violation - width: 1 - - - ControllerData: - id: 0x24 - cycletime: 10 - - signals: - - averageVelocity: - description: Average velocity. - # minimum: -12.0 - # maximum: 12.0 - unit: m/s - twos_complement: true - scale: 0.001 - width: 16 - - - desiredAcceleration: - description: Desired acceleration. - # minimum: -12.0 - # maximum: 12.0 - unit: m/s - twos_complement: true - scale: 0.001 - width: 16 - - - ControllerGains: - from_template: PIDGains - id: 0x25 - cycletime: 10 - - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD4 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE4 - - - EncoderData: - from_template: EncoderData - id: 0x14 - - - VelocityCommand: - from_template: DBWVelocityCommand - id: 0x20 - -- CTRLBL: - rx: - - UPD_IsoTpTx_CTRL - - UPD_UpdateControl_CTRL - messages: - - IsoTpTx: - id: 0x505 - - Status: - from_template: BlStatus - id: 0x506 - -- DBW: - messages: - - ESTOP: - id: 0x0 - - signals: - - estopReason: - description: ESTOP reason. - width: 2 - enumerated_values: - - MANUAL - - TIMEOUT - - INVALID_STATE - - LIMIT_EXCEEDED - - - RawVelocityCommand: - from_template: DBWVelocityCommand - id: 0x667 - - - SetVelocityGains: - from_template: PIDGains - id: 0x777 - - - SteeringCommand: - id: 0x21 - cycletime: 10 - - signals: - - steeringAngle: - description: Absolute steering angle in radians. - # minimum: -0.471238898 - # maximum: 0.471238898 - scale: 0.000000001 - twos_complement: true - width: 32 - - - VelocityCommand: - id: 0x666 - cycletime: 10 - - signals: - - linearVelocity: - description: Velocity in m/s - # maximum: 100.0 - scale: 0.1 - width: 10 - # TODO: determine realistic bounds -# - angularVelocity: -# description: Velocity in rad/s - -- ENCF: - rx: - - DBW_ESTOP - messages: - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD3 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE3 - - - EncoderData: - from_template: EncoderData - id: 0x13 - -- ODRIVE: - -rx: - - STEER_ODriveVelocity - messages: - - ControllerError: - id: 0x31D - cycletime: 10 - - signals: - - controllerError: - description: ODrive controller error. - width: 32 - - enumerated_values: - - NONE: 0x00 - - OVERSPEED: 0x01 - - INVALID_INPUT_MODE: 0x02 - - UNSTABLE_GAIN: 0x04 - - INVALID_MIRROR_AXIS: 0x08 - - INVALID_LOAD_ENCODER: 0x10 - - INVALID_ESTIMATE: 0x20 - - INVALID_CIRCULAR_RANGE: 0x40 - - SPINOUT_DETECTED: 0x80 - - - EncoderError: - id: 0x304 - cycletime: 10 - - signals: - - encoderError: - description: ODrive encoder error. - width: 32 - - enumerated_values: - - NONE: 0x000 - - UNSTABLE_GAIN: 0x001 - - CPR_POLEPAIRS_MISMATCH: 0x002 - - NO_RESPONSE: 0x004 - - UNSUPPORTED_ENCODER_MODE: 0x008 - - ILLEGAL_HALL_STATE: 0x010 - - INDEX_NOT_FOUND_YET: 0x020 - - ABS_SPI_TIMEOUT: 0x040 - - ABS_SPI_COM_FAIL: 0x080 - - ABS_SPI_NOT_READY: 0x100 - - HALL_NOT_CALIBRATED_YET: 0x200 - - - MotorError: - id: 0x303 - cycletime: 10 - - signals: - - motorError: - description: ODrive motor error. - width: 32 - - enumerated_values: - - NONE: 0x000000000 - - PHASE_RESISTANCE_OUT_OF_RANGE: 0x000000001 - - PHASE_INDUCTANCE_OUT_OF_RANGE: 0x000000002 - - DRV_FAULT: 0x000000008 - - CONTROL_DEADLINE_MISSED: 0x000000010 - - MODULATION_MAGNITUDE: 0x000000080 - - CURRENT_SENSE_SATURATION: 0x000000400 - - CURRENT_LIMIT_VIOLATION: 0x000001000 - - MODULATION_IS_NAN: 0x000010000 - - MOTOR_THERMISTOR_OVER_TEMP: 0x000020000 - - FET_THERMISTOR_OVER_TEMP: 0x000040000 - - TIMER_UPDATE_MISSED: 0x000080000 - - CURRENT_MEASUREMENT_UNAVAILABLE: 0x000100000 - - CONTROLLER_FAILED: 0x000200000 - - I_BUS_OUT_OF_RANGE: 0x000400000 - - BRAKE_RESISTOR_DISARMED: 0x000800000 - - SYSTEM_LEVEL: 0x001000000 - - BAD_TIMING: 0x002000000 - - UNKNOWN_PHASE_ESTIMATE: 0x004000000 - - UNKNOWN_PHASE_VEL: 0x008000000 - - UNKNOWN_TORQUE: 0x010000000 - - UNKNOWN_CURRENT_COMMAND: 0x020000000 - - UNKNOWN_CURRENT_MEASUREMENT: 0x040000000 - - UNKNOWN_VBUS_VOLTAGE: 0x080000000 - - UNKNOWN_VOLTAGE_COMMAND: 0x100000000 - - UNKNOWN_GAINS: 0x200000000 - - CONTROLLER_INITIALIZING: 0x400000000 - - UNBALANCED_PHASES: 0x800000000 - - - Status: - id: 0x301 - cycletime: 10 - - signals: - - axisError: - description: Axis error. - width: 32 - - enumerated_values: - - NONE: 0x00000 - - INVALID_STATE: 0x00001 - - MOTOR_FAILED: 0x00040 - - SENSORLESS_ESTIMATOR_FAILED: 0x00080 - - ENCODER_FAILED: 0x00100 - - CONTROLLER_FAILED: 0x00200 - - WATCHDOG_TIMER_EXPIRED: 0x00800 - - MIN_ENDSTOP_PRESSED: 0x01000 - - MAX_ENDSTOP_PRESSED: 0x02000 - - ESTOP_REQUESTED: 0x04000 - - HOMING_WITHOUT_ENDSTOP: 0x20000 - - OVER_TEMP: 0x40000 - - UNKNOWN_POSITION: 0x80000 - - - axisState: - description: Axis state. - width: 8 - - enumerated_values: - - UNDEFINED: 0x00 - - IDLE: 0x01 - - STARTUP_SEQUENCE: 0x02 - - FULL_CALIBRATION_SEQUENCE: 0x03 - - MOTOR_CALIBRATION: 0x04 - - ENCODER_INDEX_SEARCH: 0x06 - - ENCODER_OFFSET_CALIBRATION: 0x07 - - CLOSED_LOOP_CONTROL: 0x08 - - LOCKIN_SPIN: 0x09 - - ENCODER_DIR_FIND: 0x0A - - HOMING: 0x0B - - ENCODER_HALL_POLARITY_CALIBRATION: 0x0C - - ENCODER_HALL_PHASE_CALIBRATION: 0x0D - - - motorErrorAlarm: - description: Motor error alarm. - start_bit: 40 - width: 1 - - - encoderErrorAlarm: - description: Encoder error alarm. - start_bit: 48 - width: 1 - - - controllerErrorAlarm: - description: Controller error alarm. - start_bit: 56 - width: 1 - - - trajectoryDone: - description: Trajectory done. - start_bit: 63 - width: 1 - - -- PB: - rx: - - DBW_ESTOP - messages: - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD5 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE5 - - - ParkingBrakeData: - id: 0x15 - cycletime: 100 - - signals: - - pbSet: - description: State of the parking brake. - width: 1 - - - magnetEnergized: - description: State of the parking brake magnet. - width: 1 - - - armedESTOP: - description: State of the ESTOP arming. - width: 1 - -- STEER: - rx: - - DBW_ESTOP - - DBW_SteeringCommand - - ODRIVE_Status - - SUP_Authorization - - WHL_AbsoluteEncoder - - UPD_UpdateControl_STEER - messages: - - Alarms: - id: 0x17 - cycletime: 10 - - signals: - - alarmsRaised: - description: Alarms raised. - width: 1 - - - odriveCalibrationAlarm: - description: ODrive calibration necessary. - width: 1 - - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD6 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE6 - - - ODriveClearErrors: - id: 0x318 - - # unused - - ODriveControllerMode: - id: 0x30B - - signals: - - odriveControlMode: - description: ODrive controller mode. - width: 32 - - enumerated_values: - - VOLTAGE_CONTROL: 0 - - TORQUE_CONTROL: 1 - - VELOCITY_CONTROL: 2 - - POSITION_CONTROL: 3 - - - odriveInputMode: - description: ODrive input mode. - width: 32 - - enumerated_values: - - INACTIVE: 0x00 - - PASSTHROUGH: 0x01 - - VEL_RAMP: 0x02 - - POS_FILTER: 0x03 - - MIX_CHANNELS: 0x04 - - TRAP_TRAJ: 0x05 - - TORQUE_RAMP: 0x06 - - MIRROR: 0x07 - - TUNING: 0x08 - - # unused - - ODriveESTOP: - id: 0x302 - - # unused - - ODriveReboot: - id: 0x316 - - - ODriveRequestState: - id: 0x307 - - signals: - - odriveRequestState: - description: ODrive state request. - width: 32 - - enumerated_values: - - UNDEFINED: 0x00 - - IDLE: 0x01 - - STARTUP_SEQUENCE: 0x02 - - FULL_CALIBRATION_SEQUENCE: 0x03 - - MOTOR_CALIBRATION: 0x04 - - ENCODER_INDEX_SEARCH: 0x06 - - ENCODER_OFFSET_CALIBRATION: 0x07 - - CLOSED_LOOP_CONTROL: 0x08 - - LOCKIN_SPIN: 0x09 - - ENCODER_DIR_FIND: 0x0A - - HOMING: 0x0B - - ENCODER_HALL_POLARITY_CALIBRATION: 0x0C - - ENCODER_HALL_PHASE_CALIBRATION: 0x0D - - - ODriveVelocity: - id: 0x30D - cycletime: 10 - - signals: - - odriveVelocity: - description: ODrive velocity command (IEEE 754). - width: 32 - unit: rev - - - odriveTorqueFeedForward: - description: ODrive torque feed forward (IEEE 754). - width: 32 - unit: rev/s - - - SteeringData: - id: 0x16 - cycletime: 10 - - signals: - - state: - description: Steering state. - - enumerated_values: - - READY - - CALIBRATING - - NEEDS_CALIBRATION -- STEERBL: - rx: - - UPD_IsoTpTx_STEER - - UPD_UpdateControl_STEER - messages: - - IsoTpTx: - id: 0x507 - - Status: - from_template: BlStatus - id: 0x508 - -- SUP: - rx: - - BRAKE_NodeStatus - - CTRL_Alarms - - CTRL_NodeStatus - - CTRL_VelocityCommand - - DBW_ESTOP - - DBW_RawVelocityCommand - - DBW_SteeringCommand - - DBW_VelocityCommand - - STEER_NodeStatus - - STEER_SteeringData - - THROTTLE_NodeStatus - - UPD_UpdateControl_SUP # bootloader - messages: - - Authorization: - id: 0x1A - cycletime: 10 - - signals: - - brakeAuthorized: - description: Brake authorization. - width: 1 - - throttleAuthorized: - description: Throttle authorization. - width: 1 - - steerAuthorized: - description: Steer authorization. - width: 1 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0x1B - - - NodeInfo: - from_template: DBWNodeInfo - id: 0x1C - -- SUPBL: - rx: - - UPD_IsoTpTx_SUP - - UPD_UpdateControl_SUP - messages: - - IsoTpTx: - id: 0x509 - - Status: - from_template: BlStatus - id: 0x50a - -- TEST: - rx: "*" - -- UPD: - rx: - - BLINK_NodeStatus - - BLINKBL_IsoTpTx - - BLINKBL_Status - - - BRAKE_NodeStatus - - BRAKEBL_IsoTpTx - - BRAKEBL_Status - - - CTRL_NodeStatus - - CTRLBL_IsoTpTx - - CTRLBL_Status - - - STEER_NodeStatus - - STEERBL_IsoTpTx - - STEERBL_Status - - - SUP_NodeStatus - - SUPBL_IsoTpTx - - SUPBL_Status - - - THROTTLE_NodeStatus - - THROTTLEBL_IsoTpTx - - THROTTLEBL_Status - messages: - - IsoTpTx_BLINK: - id: 0x530 - - IsoTpTx_BRAKE: - id: 0x531 - - IsoTpTx_CTRL: - id: 0x532 - - IsoTpTx_STEER: - id: 0x533 - - IsoTpTx_SUP: - id: 0x534 - - IsoTpTx_THROTTLE: - id: 0x535 - - UpdateControl_BLINK: - from_template: UpdateControl - id: 0x5A0 - - UpdateControl_BRAKE: - from_template: UpdateControl - id: 0x5A1 - - UpdateControl_CTRL: - from_template: UpdateControl - id: 0x5A2 - - UpdateControl_STEER: - from_template: UpdateControl - id: 0x5A3 - - UpdateControl_SUP: - from_template: UpdateControl - id: 0x5A4 - - UpdateControl_THROTTLE: - from_template: UpdateControl - id: 0x5A5 - -- THROTTLE: - rx: - - DBW_ESTOP - - CTRL_VelocityCommand - - SUP_Authorization - - UPD_UpdateControl_THROTTLE # bootloader - messages: - - NodeInfo: - from_template: DBWNodeInfo - id: 0xD1 - - - NodeStatus: - from_template: DBWNodeStatus - id: 0xE1 - - - AccelData: - id: 0x10 - cycletime: 100 - - signals: - - throttleADutyCycle: - description: Throttle A duty cycle. - width: 10 - - - throttleFDutyCycle: - description: Throttle F duty cycle. - width: 10 - - - percent: - description: Percentage commanded. - # minimum: 0.0 - # maximum: 100.0 - width: 10 - unit: percent - scale: 0.1 - - - relayState: - description: Current relay state. - width: 1 - -- THROTTLEBL: - rx: - - UPD_IsoTpTx_THROTTLE - - UPD_UpdateControl_THROTTLE - messages: - - IsoTpTx: - id: 0x50b - - Status: - from_template: BlStatus - id: 0x50c - -- WHL: - messages: - - AbsoluteEncoder: - id: 0x1E5 - cycletime: 10 - - signals: - - foo: - description: Foo. - width: 8 - - # TODO: add big endian support to OpenCAN - # - # this signal is a signed big-endian value - # OpenCAN will decode this signal into an unsigned int - # it is the job of the programmer to re-encode this value - # into a signed int - - encoder: - description: Absolute encoder position. - width: 16 - - - bar: - description: Bar. - width: 40 + - BLINK: + rx: + - DBW_ESTOP + - UPD_UpdateControl_BLINK # bootloader + messages: + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD0 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE0 + + - BLINKBL: + rx: + - UPD_IsoTpTx_BLINK + - UPD_UpdateControl_BLINK + messages: + - IsoTpTx: + id: 0x501 + - Status: + from_template: BlStatus + id: 0x502 + + - BRAKE: + rx: + - CTRL_VelocityCommand + - DBW_ESTOP + - DBW_VelocityCommand + - SUP_Authorization + - UPD_UpdateControl_BRAKE # bootloader + messages: + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD2 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE2 + + - BrakeData: + id: 0x11 + cycletime: 100 + + signals: + - dutyCycle: + description: Brake duty cycle. + width: 10 + + - percent: + description: Percentage commanded. + # minimum: 0.0 + # maximum: 100.0 + width: 10 + unit: percent + scale: 0.1 + - BRAKEBL: + rx: + - UPD_IsoTpTx_BRAKE + - UPD_UpdateControl_BRAKE + messages: + - IsoTpTx: + id: 0x503 + - Status: + from_template: BlStatus + id: 0x504 + + - CTRL: + rx: + - DBW_ESTOP + - DBW_SetVelocityGains + - DBW_RawVelocityCommand + - DBW_VelocityCommand + - UPD_UpdateControl_CTRL # bootloader + messages: + - Alarms: + id: 0x22 + cycletime: 10 + + signals: + - alarmsRaised: + description: Alarms raised + width: 1 + - speedAlarm: + description: Speed violation + width: 1 + + - ControllerData: + id: 0x24 + cycletime: 10 + + signals: + - averageVelocity: + description: Average velocity. + # minimum: -12.0 + # maximum: 12.0 + unit: m/s + twos_complement: true + scale: 0.001 + width: 16 + + - desiredAcceleration: + description: Desired acceleration. + # minimum: -12.0 + # maximum: 12.0 + unit: m/s + twos_complement: true + scale: 0.001 + width: 16 + + - ControllerGains: + from_template: PIDGains + id: 0x25 + cycletime: 10 + + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD4 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE4 + + - EncoderData: + from_template: EncoderData + id: 0x14 + + - VelocityCommand: + from_template: DBWVelocityCommand + id: 0x20 + + - CTRLBL: + rx: + - UPD_IsoTpTx_CTRL + - UPD_UpdateControl_CTRL + messages: + - IsoTpTx: + id: 0x505 + - Status: + from_template: BlStatus + id: 0x506 + + - DBW: + messages: + - ESTOP: + id: 0x0 + + signals: + - estopReason: + description: ESTOP reason. + width: 2 + enumerated_values: + - MANUAL + - TIMEOUT + - INVALID_STATE + - LIMIT_EXCEEDED + + - RawVelocityCommand: + from_template: DBWVelocityCommand + id: 0x667 + + - SetVelocityGains: + from_template: PIDGains + id: 0x777 + + - SteeringCommand: + id: 0x21 + cycletime: 10 + + signals: + - steeringAngle: + description: Absolute steering angle in radians. + # minimum: -0.471238898 + # maximum: 0.471238898 + scale: 0.000000001 + twos_complement: true + width: 32 + + - VelocityCommand: + id: 0x666 + cycletime: 10 + + signals: + - linearVelocity: + description: Velocity in m/s + # maximum: 100.0 + scale: 0.1 + width: 10 + # TODO: determine realistic bounds + + - ENCF: + rx: + - DBW_ESTOP + messages: + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD3 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE3 + + - EncoderData: + from_template: EncoderData + id: 0x13 + + - ODRIVE: + -rx: + - STEER_ODriveVelocity + messages: + - ControllerError: + id: 0x31D + cycletime: 10 + + signals: + - controllerError: + description: ODrive controller error. + width: 32 + + enumerated_values: + - NONE: 0x00 + - OVERSPEED: 0x01 + - INVALID_INPUT_MODE: 0x02 + - UNSTABLE_GAIN: 0x04 + - INVALID_MIRROR_AXIS: 0x08 + - INVALID_LOAD_ENCODER: 0x10 + - INVALID_ESTIMATE: 0x20 + - INVALID_CIRCULAR_RANGE: 0x40 + - SPINOUT_DETECTED: 0x80 + + - EncoderError: + id: 0x304 + cycletime: 10 + + signals: + - encoderError: + description: ODrive encoder error. + width: 32 + + enumerated_values: + - NONE: 0x000 + - UNSTABLE_GAIN: 0x001 + - CPR_POLEPAIRS_MISMATCH: 0x002 + - NO_RESPONSE: 0x004 + - UNSUPPORTED_ENCODER_MODE: 0x008 + - ILLEGAL_HALL_STATE: 0x010 + - INDEX_NOT_FOUND_YET: 0x020 + - ABS_SPI_TIMEOUT: 0x040 + - ABS_SPI_COM_FAIL: 0x080 + - ABS_SPI_NOT_READY: 0x100 + - HALL_NOT_CALIBRATED_YET: 0x200 + + - MotorError: + id: 0x303 + cycletime: 10 + + signals: + - motorError: + description: ODrive motor error. + width: 32 + + enumerated_values: + - NONE: 0x000000000 + - PHASE_RESISTANCE_OUT_OF_RANGE: 0x000000001 + - PHASE_INDUCTANCE_OUT_OF_RANGE: 0x000000002 + - DRV_FAULT: 0x000000008 + - CONTROL_DEADLINE_MISSED: 0x000000010 + - MODULATION_MAGNITUDE: 0x000000080 + - CURRENT_SENSE_SATURATION: 0x000000400 + - CURRENT_LIMIT_VIOLATION: 0x000001000 + - MODULATION_IS_NAN: 0x000010000 + - MOTOR_THERMISTOR_OVER_TEMP: 0x000020000 + - FET_THERMISTOR_OVER_TEMP: 0x000040000 + - TIMER_UPDATE_MISSED: 0x000080000 + - CURRENT_MEASUREMENT_UNAVAILABLE: 0x000100000 + - CONTROLLER_FAILED: 0x000200000 + - I_BUS_OUT_OF_RANGE: 0x000400000 + - BRAKE_RESISTOR_DISARMED: 0x000800000 + - SYSTEM_LEVEL: 0x001000000 + - BAD_TIMING: 0x002000000 + - UNKNOWN_PHASE_ESTIMATE: 0x004000000 + - UNKNOWN_PHASE_VEL: 0x008000000 + - UNKNOWN_TORQUE: 0x010000000 + - UNKNOWN_CURRENT_COMMAND: 0x020000000 + - UNKNOWN_CURRENT_MEASUREMENT: 0x040000000 + - UNKNOWN_VBUS_VOLTAGE: 0x080000000 + - UNKNOWN_VOLTAGE_COMMAND: 0x100000000 + - UNKNOWN_GAINS: 0x200000000 + - CONTROLLER_INITIALIZING: 0x400000000 + - UNBALANCED_PHASES: 0x800000000 + + - Status: + id: 0x301 + cycletime: 10 + + signals: + - axisError: + description: Axis error. + width: 32 + + enumerated_values: + - NONE: 0x00000 + - INVALID_STATE: 0x00001 + - MOTOR_FAILED: 0x00040 + - SENSORLESS_ESTIMATOR_FAILED: 0x00080 + - ENCODER_FAILED: 0x00100 + - CONTROLLER_FAILED: 0x00200 + - WATCHDOG_TIMER_EXPIRED: 0x00800 + - MIN_ENDSTOP_PRESSED: 0x01000 + - MAX_ENDSTOP_PRESSED: 0x02000 + - ESTOP_REQUESTED: 0x04000 + - HOMING_WITHOUT_ENDSTOP: 0x20000 + - OVER_TEMP: 0x40000 + - UNKNOWN_POSITION: 0x80000 + + - axisState: + description: Axis state. + width: 8 + + enumerated_values: + - UNDEFINED: 0x00 + - IDLE: 0x01 + - STARTUP_SEQUENCE: 0x02 + - FULL_CALIBRATION_SEQUENCE: 0x03 + - MOTOR_CALIBRATION: 0x04 + - ENCODER_INDEX_SEARCH: 0x06 + - ENCODER_OFFSET_CALIBRATION: 0x07 + - CLOSED_LOOP_CONTROL: 0x08 + - LOCKIN_SPIN: 0x09 + - ENCODER_DIR_FIND: 0x0A + - HOMING: 0x0B + - ENCODER_HALL_POLARITY_CALIBRATION: 0x0C + - ENCODER_HALL_PHASE_CALIBRATION: 0x0D + + - motorErrorAlarm: + description: Motor error alarm. + start_bit: 40 + width: 1 + + - encoderErrorAlarm: + description: Encoder error alarm. + start_bit: 48 + width: 1 + + - controllerErrorAlarm: + description: Controller error alarm. + start_bit: 56 + width: 1 + + - trajectoryDone: + description: Trajectory done. + start_bit: 63 + width: 1 + + - PB: + rx: + - DBW_ESTOP + messages: + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD5 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE5 + + - ParkingBrakeData: + id: 0x15 + cycletime: 100 + + signals: + - pbSet: + description: State of the parking brake. + width: 1 + + - magnetEnergized: + description: State of the parking brake magnet. + width: 1 + + - armedESTOP: + description: State of the ESTOP arming. + width: 1 + + - STEER: + rx: + - DBW_ESTOP + - DBW_SteeringCommand + - ODRIVE_Status + - SUP_Authorization + - WHL_AbsoluteEncoder + - UPD_UpdateControl_STEER + messages: + - Alarms: + id: 0x17 + cycletime: 10 + + signals: + - alarmsRaised: + description: Alarms raised. + width: 1 + + - odriveCalibrationAlarm: + description: ODrive calibration necessary. + width: 1 + + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD6 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE6 + + - ODriveClearErrors: + id: 0x318 + + # unused + - ODriveControllerMode: + id: 0x30B + + signals: + - odriveControlMode: + description: ODrive controller mode. + width: 32 + + enumerated_values: + - VOLTAGE_CONTROL: 0 + - TORQUE_CONTROL: 1 + - VELOCITY_CONTROL: 2 + - POSITION_CONTROL: 3 + + - odriveInputMode: + description: ODrive input mode. + width: 32 + + enumerated_values: + - INACTIVE: 0x00 + - PASSTHROUGH: 0x01 + - VEL_RAMP: 0x02 + - POS_FILTER: 0x03 + - MIX_CHANNELS: 0x04 + - TRAP_TRAJ: 0x05 + - TORQUE_RAMP: 0x06 + - MIRROR: 0x07 + - TUNING: 0x08 + + # unused + - ODriveESTOP: + id: 0x302 + + # unused + - ODriveReboot: + id: 0x316 + + - ODriveRequestState: + id: 0x307 + + signals: + - odriveRequestState: + description: ODrive state request. + width: 32 + + enumerated_values: + - UNDEFINED: 0x00 + - IDLE: 0x01 + - STARTUP_SEQUENCE: 0x02 + - FULL_CALIBRATION_SEQUENCE: 0x03 + - MOTOR_CALIBRATION: 0x04 + - ENCODER_INDEX_SEARCH: 0x06 + - ENCODER_OFFSET_CALIBRATION: 0x07 + - CLOSED_LOOP_CONTROL: 0x08 + - LOCKIN_SPIN: 0x09 + - ENCODER_DIR_FIND: 0x0A + - HOMING: 0x0B + - ENCODER_HALL_POLARITY_CALIBRATION: 0x0C + - ENCODER_HALL_PHASE_CALIBRATION: 0x0D + + - ODriveVelocity: + id: 0x30D + cycletime: 10 + + signals: + - odriveVelocity: + description: ODrive velocity command (IEEE 754). + width: 32 + unit: rev + + - odriveTorqueFeedForward: + description: ODrive torque feed forward (IEEE 754). + width: 32 + unit: rev/s + + - SteeringData: + id: 0x16 + cycletime: 10 + + signals: + - state: + description: Steering state. + + enumerated_values: + - READY + - CALIBRATING + - NEEDS_CALIBRATION + - STEERBL: + rx: + - UPD_IsoTpTx_STEER + - UPD_UpdateControl_STEER + messages: + - IsoTpTx: + id: 0x507 + - Status: + from_template: BlStatus + id: 0x508 + + - SUP: + rx: + - BRAKE_NodeStatus + - CTRL_Alarms + - CTRL_NodeStatus + - CTRL_VelocityCommand + - DBW_ESTOP + - DBW_RawVelocityCommand + - DBW_SteeringCommand + - DBW_VelocityCommand + - STEER_NodeStatus + - STEER_SteeringData + - THROTTLE_NodeStatus + - UPD_UpdateControl_SUP # bootloader + messages: + - Authorization: + id: 0x1A + cycletime: 10 + + signals: + - brakeAuthorized: + description: Brake authorization. + width: 1 + - throttleAuthorized: + description: Throttle authorization. + width: 1 + - steerAuthorized: + description: Steer authorization. + width: 1 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0x1B + + - NodeInfo: + from_template: DBWNodeInfo + id: 0x1C + + - SUPBL: + rx: + - UPD_IsoTpTx_SUP + - UPD_UpdateControl_SUP + messages: + - IsoTpTx: + id: 0x509 + - Status: + from_template: BlStatus + id: 0x50a + + - TEST: + rx: '*' + + - UPD: + rx: + - BLINK_NodeStatus + - BLINKBL_IsoTpTx + - BLINKBL_Status + + - BRAKE_NodeStatus + - BRAKEBL_IsoTpTx + - BRAKEBL_Status + + - CTRL_NodeStatus + - CTRLBL_IsoTpTx + - CTRLBL_Status + + - STEER_NodeStatus + - STEERBL_IsoTpTx + - STEERBL_Status + + - SUP_NodeStatus + - SUPBL_IsoTpTx + - SUPBL_Status + + - THROTTLE_NodeStatus + - THROTTLEBL_IsoTpTx + - THROTTLEBL_Status + messages: + - IsoTpTx_BLINK: + id: 0x530 + - IsoTpTx_BRAKE: + id: 0x531 + - IsoTpTx_CTRL: + id: 0x532 + - IsoTpTx_STEER: + id: 0x533 + - IsoTpTx_SUP: + id: 0x534 + - IsoTpTx_THROTTLE: + id: 0x535 + - UpdateControl_BLINK: + from_template: UpdateControl + id: 0x5A0 + - UpdateControl_BRAKE: + from_template: UpdateControl + id: 0x5A1 + - UpdateControl_CTRL: + from_template: UpdateControl + id: 0x5A2 + - UpdateControl_STEER: + from_template: UpdateControl + id: 0x5A3 + - UpdateControl_SUP: + from_template: UpdateControl + id: 0x5A4 + - UpdateControl_THROTTLE: + from_template: UpdateControl + id: 0x5A5 + + - THROTTLE: + rx: + - DBW_ESTOP + - CTRL_VelocityCommand + - SUP_Authorization + - UPD_UpdateControl_THROTTLE # bootloader + messages: + - NodeInfo: + from_template: DBWNodeInfo + id: 0xD1 + + - NodeStatus: + from_template: DBWNodeStatus + id: 0xE1 + + - AccelData: + id: 0x10 + cycletime: 100 + + signals: + - throttleADutyCycle: + description: Throttle A duty cycle. + width: 10 + + - throttleFDutyCycle: + description: Throttle F duty cycle. + width: 10 + + - percent: + description: Percentage commanded. + # minimum: 0.0 + # maximum: 100.0 + width: 10 + unit: percent + scale: 0.1 + + - relayState: + description: Current relay state. + width: 1 + + - THROTTLEBL: + rx: + - UPD_IsoTpTx_THROTTLE + - UPD_UpdateControl_THROTTLE + messages: + - IsoTpTx: + id: 0x50b + - Status: + from_template: BlStatus + id: 0x50c + + - WHL: + messages: + - AbsoluteEncoder: + id: 0x1E5 + cycletime: 10 + + signals: + - foo: + description: Foo. + width: 8 + + # TODO: add big endian support to OpenCAN + # + # this signal is a signed big-endian value + # OpenCAN will decode this signal into an unsigned int + # it is the job of the programmer to re-encode this value + # into a signed int + - encoder: + description: Absolute encoder position. + width: 16 + + - bar: + description: Bar. + width: 40 diff --git a/pyproject.toml b/pyproject.toml index c168672ba..362e23828 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -12,7 +12,7 @@ authors = [ ] license = {'text' = 'GPL-3.0-only'} -requires-python = '>=3.11' +requires-python = '>=3.10' dependencies = [ 'black', 'can-isotp', @@ -26,6 +26,8 @@ dependencies = [ 'ruff', 'strictyaml', 'tqdm', + 'yamlfix', + 'yamllint', ] [project.urls] @@ -53,3 +55,10 @@ force-single-line = true [tool.setuptools.packages.find] exclude = ['*'] + +[tool.yamlfix] +exclude = ['common/cantools/**/*.yml', 'deps/*.yml'] +none_representation = '~' +section_whitelines = 1 +sequence_style = 'block_style' +whitelines = 1 diff --git a/requirements.txt b/requirements.txt index 029ae6da4..6dccc9ca2 100644 --- a/requirements.txt +++ b/requirements.txt @@ -111,106 +111,108 @@ cfgv==3.4.0 \ --hash=sha256:b7265b1f29fd3316bfcd2b330d63d024f2bfd8bcb8b0272f8e19a504856c48f9 \ --hash=sha256:e52591d4c5f5dead8e0f673fb16db7949d2cfb3f7da4582893288f0ded8fe560 # via pre-commit -charset-normalizer==3.3.0 \ - --hash=sha256:02673e456dc5ab13659f85196c534dc596d4ef260e4d86e856c3b2773ce09843 \ - --hash=sha256:02af06682e3590ab952599fbadac535ede5d60d78848e555aa58d0c0abbde786 \ - --hash=sha256:03680bb39035fbcffe828eae9c3f8afc0428c91d38e7d61aa992ef7a59fb120e \ - --hash=sha256:0570d21da019941634a531444364f2482e8db0b3425fcd5ac0c36565a64142c8 \ - --hash=sha256:09c77f964f351a7369cc343911e0df63e762e42bac24cd7d18525961c81754f4 \ - --hash=sha256:0d3d5b7db9ed8a2b11a774db2bbea7ba1884430a205dbd54a32d61d7c2a190fa \ - --hash=sha256:1063da2c85b95f2d1a430f1c33b55c9c17ffaf5e612e10aeaad641c55a9e2b9d \ - --hash=sha256:12ebea541c44fdc88ccb794a13fe861cc5e35d64ed689513a5c03d05b53b7c82 \ - --hash=sha256:153e7b6e724761741e0974fc4dcd406d35ba70b92bfe3fedcb497226c93b9da7 \ - --hash=sha256:15b26ddf78d57f1d143bdf32e820fd8935d36abe8a25eb9ec0b5a71c82eb3895 \ - --hash=sha256:1872d01ac8c618a8da634e232f24793883d6e456a66593135aeafe3784b0848d \ - --hash=sha256:187d18082694a29005ba2944c882344b6748d5be69e3a89bf3cc9d878e548d5a \ - --hash=sha256:1b2919306936ac6efb3aed1fbf81039f7087ddadb3160882a57ee2ff74fd2382 \ - --hash=sha256:232ac332403e37e4a03d209a3f92ed9071f7d3dbda70e2a5e9cff1c4ba9f0678 \ - --hash=sha256:23e8565ab7ff33218530bc817922fae827420f143479b753104ab801145b1d5b \ - --hash=sha256:24817cb02cbef7cd499f7c9a2735286b4782bd47a5b3516a0e84c50eab44b98e \ - --hash=sha256:249c6470a2b60935bafd1d1d13cd613f8cd8388d53461c67397ee6a0f5dce741 \ - --hash=sha256:24a91a981f185721542a0b7c92e9054b7ab4fea0508a795846bc5b0abf8118d4 \ - --hash=sha256:2502dd2a736c879c0f0d3e2161e74d9907231e25d35794584b1ca5284e43f596 \ - --hash=sha256:250c9eb0f4600361dd80d46112213dff2286231d92d3e52af1e5a6083d10cad9 \ - --hash=sha256:278c296c6f96fa686d74eb449ea1697f3c03dc28b75f873b65b5201806346a69 \ - --hash=sha256:2935ffc78db9645cb2086c2f8f4cfd23d9b73cc0dc80334bc30aac6f03f68f8c \ - --hash=sha256:2f4a0033ce9a76e391542c182f0d48d084855b5fcba5010f707c8e8c34663d77 \ - --hash=sha256:30a85aed0b864ac88309b7d94be09f6046c834ef60762a8833b660139cfbad13 \ - --hash=sha256:380c4bde80bce25c6e4f77b19386f5ec9db230df9f2f2ac1e5ad7af2caa70459 \ - --hash=sha256:3ae38d325b512f63f8da31f826e6cb6c367336f95e418137286ba362925c877e \ - --hash=sha256:3b447982ad46348c02cb90d230b75ac34e9886273df3a93eec0539308a6296d7 \ - --hash=sha256:3debd1150027933210c2fc321527c2299118aa929c2f5a0a80ab6953e3bd1908 \ - --hash=sha256:4162918ef3098851fcd8a628bf9b6a98d10c380725df9e04caf5ca6dd48c847a \ - --hash=sha256:468d2a840567b13a590e67dd276c570f8de00ed767ecc611994c301d0f8c014f \ - --hash=sha256:4cc152c5dd831641e995764f9f0b6589519f6f5123258ccaca8c6d34572fefa8 \ - --hash=sha256:542da1178c1c6af8873e143910e2269add130a299c9106eef2594e15dae5e482 \ - --hash=sha256:557b21a44ceac6c6b9773bc65aa1b4cc3e248a5ad2f5b914b91579a32e22204d \ - --hash=sha256:5707a746c6083a3a74b46b3a631d78d129edab06195a92a8ece755aac25a3f3d \ - --hash=sha256:588245972aca710b5b68802c8cad9edaa98589b1b42ad2b53accd6910dad3545 \ - --hash=sha256:5adf257bd58c1b8632046bbe43ee38c04e1038e9d37de9c57a94d6bd6ce5da34 \ - --hash=sha256:619d1c96099be5823db34fe89e2582b336b5b074a7f47f819d6b3a57ff7bdb86 \ - --hash=sha256:63563193aec44bce707e0c5ca64ff69fa72ed7cf34ce6e11d5127555756fd2f6 \ - --hash=sha256:67b8cc9574bb518ec76dc8e705d4c39ae78bb96237cb533edac149352c1f39fe \ - --hash=sha256:6a685067d05e46641d5d1623d7c7fdf15a357546cbb2f71b0ebde91b175ffc3e \ - --hash=sha256:70f1d09c0d7748b73290b29219e854b3207aea922f839437870d8cc2168e31cc \ - --hash=sha256:750b446b2ffce1739e8578576092179160f6d26bd5e23eb1789c4d64d5af7dc7 \ - --hash=sha256:7966951325782121e67c81299a031f4c115615e68046f79b85856b86ebffc4cd \ - --hash=sha256:7b8b8bf1189b3ba9b8de5c8db4d541b406611a71a955bbbd7385bbc45fcb786c \ - --hash=sha256:7f5d10bae5d78e4551b7be7a9b29643a95aded9d0f602aa2ba584f0388e7a557 \ - --hash=sha256:805dfea4ca10411a5296bcc75638017215a93ffb584c9e344731eef0dcfb026a \ - --hash=sha256:81bf654678e575403736b85ba3a7867e31c2c30a69bc57fe88e3ace52fb17b89 \ - --hash=sha256:82eb849f085624f6a607538ee7b83a6d8126df6d2f7d3b319cb837b289123078 \ - --hash=sha256:85a32721ddde63c9df9ebb0d2045b9691d9750cb139c161c80e500d210f5e26e \ - --hash=sha256:86d1f65ac145e2c9ed71d8ffb1905e9bba3a91ae29ba55b4c46ae6fc31d7c0d4 \ - --hash=sha256:86f63face3a527284f7bb8a9d4f78988e3c06823f7bea2bd6f0e0e9298ca0403 \ - --hash=sha256:8eaf82f0eccd1505cf39a45a6bd0a8cf1c70dcfc30dba338207a969d91b965c0 \ - --hash=sha256:93aa7eef6ee71c629b51ef873991d6911b906d7312c6e8e99790c0f33c576f89 \ - --hash=sha256:96c2b49eb6a72c0e4991d62406e365d87067ca14c1a729a870d22354e6f68115 \ - --hash=sha256:9cf3126b85822c4e53aa28c7ec9869b924d6fcfb76e77a45c44b83d91afd74f9 \ - --hash=sha256:9fe359b2e3a7729010060fbca442ca225280c16e923b37db0e955ac2a2b72a05 \ - --hash=sha256:a0ac5e7015a5920cfce654c06618ec40c33e12801711da6b4258af59a8eff00a \ - --hash=sha256:a3f93dab657839dfa61025056606600a11d0b696d79386f974e459a3fbc568ec \ - --hash=sha256:a4b71f4d1765639372a3b32d2638197f5cd5221b19531f9245fcc9ee62d38f56 \ - --hash=sha256:aae32c93e0f64469f74ccc730a7cb21c7610af3a775157e50bbd38f816536b38 \ - --hash=sha256:aaf7b34c5bc56b38c931a54f7952f1ff0ae77a2e82496583b247f7c969eb1479 \ - --hash=sha256:abecce40dfebbfa6abf8e324e1860092eeca6f7375c8c4e655a8afb61af58f2c \ - --hash=sha256:abf0d9f45ea5fb95051c8bfe43cb40cda383772f7e5023a83cc481ca2604d74e \ - --hash=sha256:ac71b2977fb90c35d41c9453116e283fac47bb9096ad917b8819ca8b943abecd \ - --hash=sha256:ada214c6fa40f8d800e575de6b91a40d0548139e5dc457d2ebb61470abf50186 \ - --hash=sha256:b09719a17a2301178fac4470d54b1680b18a5048b481cb8890e1ef820cb80455 \ - --hash=sha256:b1121de0e9d6e6ca08289583d7491e7fcb18a439305b34a30b20d8215922d43c \ - --hash=sha256:b3b2316b25644b23b54a6f6401074cebcecd1244c0b8e80111c9a3f1c8e83d65 \ - --hash=sha256:b3d9b48ee6e3967b7901c052b670c7dda6deb812c309439adaffdec55c6d7b78 \ - --hash=sha256:b5bcf60a228acae568e9911f410f9d9e0d43197d030ae5799e20dca8df588287 \ - --hash=sha256:b8f3307af845803fb0b060ab76cf6dd3a13adc15b6b451f54281d25911eb92df \ - --hash=sha256:c2af80fb58f0f24b3f3adcb9148e6203fa67dd3f61c4af146ecad033024dde43 \ - --hash=sha256:c350354efb159b8767a6244c166f66e67506e06c8924ed74669b2c70bc8735b1 \ - --hash=sha256:c5a74c359b2d47d26cdbbc7845e9662d6b08a1e915eb015d044729e92e7050b7 \ - --hash=sha256:c71f16da1ed8949774ef79f4a0260d28b83b3a50c6576f8f4f0288d109777989 \ - --hash=sha256:d47ecf253780c90ee181d4d871cd655a789da937454045b17b5798da9393901a \ - --hash=sha256:d7eff0f27edc5afa9e405f7165f85a6d782d308f3b6b9d96016c010597958e63 \ - --hash=sha256:d97d85fa63f315a8bdaba2af9a6a686e0eceab77b3089af45133252618e70884 \ - --hash=sha256:db756e48f9c5c607b5e33dd36b1d5872d0422e960145b08ab0ec7fd420e9d649 \ - --hash=sha256:dc45229747b67ffc441b3de2f3ae5e62877a282ea828a5bdb67883c4ee4a8810 \ - --hash=sha256:e0fc42822278451bc13a2e8626cf2218ba570f27856b536e00cfa53099724828 \ - --hash=sha256:e39c7eb31e3f5b1f88caff88bcff1b7f8334975b46f6ac6e9fc725d829bc35d4 \ - --hash=sha256:e46cd37076971c1040fc8c41273a8b3e2c624ce4f2be3f5dfcb7a430c1d3acc2 \ - --hash=sha256:e5c1502d4ace69a179305abb3f0bb6141cbe4714bc9b31d427329a95acfc8bdd \ - --hash=sha256:edfe077ab09442d4ef3c52cb1f9dab89bff02f4524afc0acf2d46be17dc479f5 \ - --hash=sha256:effe5406c9bd748a871dbcaf3ac69167c38d72db8c9baf3ff954c344f31c4cbe \ - --hash=sha256:f0d1e3732768fecb052d90d62b220af62ead5748ac51ef61e7b32c266cac9293 \ - --hash=sha256:f5969baeaea61c97efa706b9b107dcba02784b1601c74ac84f2a532ea079403e \ - --hash=sha256:f8888e31e3a85943743f8fc15e71536bda1c81d5aa36d014a3c0c44481d7db6e \ - --hash=sha256:fc52b79d83a3fe3a360902d3f5d79073a993597d48114c29485e9431092905d8 +charset-normalizer==3.3.1 \ + --hash=sha256:06cf46bdff72f58645434d467bf5228080801298fbba19fe268a01b4534467f5 \ + --hash=sha256:0c8c61fb505c7dad1d251c284e712d4e0372cef3b067f7ddf82a7fa82e1e9a93 \ + --hash=sha256:10b8dd31e10f32410751b3430996f9807fc4d1587ca69772e2aa940a82ab571a \ + --hash=sha256:1171ef1fc5ab4693c5d151ae0fdad7f7349920eabbaca6271f95969fa0756c2d \ + --hash=sha256:17a866d61259c7de1bdadef418a37755050ddb4b922df8b356503234fff7932c \ + --hash=sha256:1d6bfc32a68bc0933819cfdfe45f9abc3cae3877e1d90aac7259d57e6e0f85b1 \ + --hash=sha256:1ec937546cad86d0dce5396748bf392bb7b62a9eeb8c66efac60e947697f0e58 \ + --hash=sha256:223b4d54561c01048f657fa6ce41461d5ad8ff128b9678cfe8b2ecd951e3f8a2 \ + --hash=sha256:2465aa50c9299d615d757c1c888bc6fef384b7c4aec81c05a0172b4400f98557 \ + --hash=sha256:28f512b9a33235545fbbdac6a330a510b63be278a50071a336afc1b78781b147 \ + --hash=sha256:2c092be3885a1b7899cd85ce24acedc1034199d6fca1483fa2c3a35c86e43041 \ + --hash=sha256:2c4c99f98fc3a1835af8179dcc9013f93594d0670e2fa80c83aa36346ee763d2 \ + --hash=sha256:31445f38053476a0c4e6d12b047b08ced81e2c7c712e5a1ad97bc913256f91b2 \ + --hash=sha256:31bbaba7218904d2eabecf4feec0d07469284e952a27400f23b6628439439fa7 \ + --hash=sha256:34d95638ff3613849f473afc33f65c401a89f3b9528d0d213c7037c398a51296 \ + --hash=sha256:352a88c3df0d1fa886562384b86f9a9e27563d4704ee0e9d56ec6fcd270ea690 \ + --hash=sha256:39b70a6f88eebe239fa775190796d55a33cfb6d36b9ffdd37843f7c4c1b5dc67 \ + --hash=sha256:3c66df3f41abee950d6638adc7eac4730a306b022570f71dd0bd6ba53503ab57 \ + --hash=sha256:3f70fd716855cd3b855316b226a1ac8bdb3caf4f7ea96edcccc6f484217c9597 \ + --hash=sha256:3f9bc2ce123637a60ebe819f9fccc614da1bcc05798bbbaf2dd4ec91f3e08846 \ + --hash=sha256:3fb765362688821404ad6cf86772fc54993ec11577cd5a92ac44b4c2ba52155b \ + --hash=sha256:45f053a0ece92c734d874861ffe6e3cc92150e32136dd59ab1fb070575189c97 \ + --hash=sha256:46fb9970aa5eeca547d7aa0de5d4b124a288b42eaefac677bde805013c95725c \ + --hash=sha256:4cb50a0335382aac15c31b61d8531bc9bb657cfd848b1d7158009472189f3d62 \ + --hash=sha256:4e12f8ee80aa35e746230a2af83e81bd6b52daa92a8afaef4fea4a2ce9b9f4fa \ + --hash=sha256:4f3100d86dcd03c03f7e9c3fdb23d92e32abbca07e7c13ebd7ddfbcb06f5991f \ + --hash=sha256:4f6e2a839f83a6a76854d12dbebde50e4b1afa63e27761549d006fa53e9aa80e \ + --hash=sha256:4f861d94c2a450b974b86093c6c027888627b8082f1299dfd5a4bae8e2292821 \ + --hash=sha256:501adc5eb6cd5f40a6f77fbd90e5ab915c8fd6e8c614af2db5561e16c600d6f3 \ + --hash=sha256:520b7a142d2524f999447b3a0cf95115df81c4f33003c51a6ab637cbda9d0bf4 \ + --hash=sha256:548eefad783ed787b38cb6f9a574bd8664468cc76d1538215d510a3cd41406cb \ + --hash=sha256:555fe186da0068d3354cdf4bbcbc609b0ecae4d04c921cc13e209eece7720727 \ + --hash=sha256:55602981b2dbf8184c098bc10287e8c245e351cd4fdcad050bd7199d5a8bf514 \ + --hash=sha256:58e875eb7016fd014c0eea46c6fa92b87b62c0cb31b9feae25cbbe62c919f54d \ + --hash=sha256:5a3580a4fdc4ac05f9e53c57f965e3594b2f99796231380adb2baaab96e22761 \ + --hash=sha256:5b70bab78accbc672f50e878a5b73ca692f45f5b5e25c8066d748c09405e6a55 \ + --hash=sha256:5ceca5876032362ae73b83347be8b5dbd2d1faf3358deb38c9c88776779b2e2f \ + --hash=sha256:61f1e3fb621f5420523abb71f5771a204b33c21d31e7d9d86881b2cffe92c47c \ + --hash=sha256:633968254f8d421e70f91c6ebe71ed0ab140220469cf87a9857e21c16687c034 \ + --hash=sha256:63a6f59e2d01310f754c270e4a257426fe5a591dc487f1983b3bbe793cf6bac6 \ + --hash=sha256:63accd11149c0f9a99e3bc095bbdb5a464862d77a7e309ad5938fbc8721235ae \ + --hash=sha256:6db3cfb9b4fcecb4390db154e75b49578c87a3b9979b40cdf90d7e4b945656e1 \ + --hash=sha256:71ef3b9be10070360f289aea4838c784f8b851be3ba58cf796262b57775c2f14 \ + --hash=sha256:7ae8e5142dcc7a49168f4055255dbcced01dc1714a90a21f87448dc8d90617d1 \ + --hash=sha256:7b6cefa579e1237ce198619b76eaa148b71894fb0d6bcf9024460f9bf30fd228 \ + --hash=sha256:800561453acdecedaac137bf09cd719c7a440b6800ec182f077bb8e7025fb708 \ + --hash=sha256:82ca51ff0fc5b641a2d4e1cc8c5ff108699b7a56d7f3ad6f6da9dbb6f0145b48 \ + --hash=sha256:851cf693fb3aaef71031237cd68699dded198657ec1e76a76eb8be58c03a5d1f \ + --hash=sha256:854cc74367180beb327ab9d00f964f6d91da06450b0855cbbb09187bcdb02de5 \ + --hash=sha256:87071618d3d8ec8b186d53cb6e66955ef2a0e4fa63ccd3709c0c90ac5a43520f \ + --hash=sha256:871d045d6ccc181fd863a3cd66ee8e395523ebfbc57f85f91f035f50cee8e3d4 \ + --hash=sha256:8aee051c89e13565c6bd366813c386939f8e928af93c29fda4af86d25b73d8f8 \ + --hash=sha256:8af5a8917b8af42295e86b64903156b4f110a30dca5f3b5aedea123fbd638bff \ + --hash=sha256:8ec8ef42c6cd5856a7613dcd1eaf21e5573b2185263d87d27c8edcae33b62a61 \ + --hash=sha256:91e43805ccafa0a91831f9cd5443aa34528c0c3f2cc48c4cb3d9a7721053874b \ + --hash=sha256:9505dc359edb6a330efcd2be825fdb73ee3e628d9010597aa1aee5aa63442e97 \ + --hash=sha256:985c7965f62f6f32bf432e2681173db41336a9c2611693247069288bcb0c7f8b \ + --hash=sha256:9a74041ba0bfa9bc9b9bb2cd3238a6ab3b7618e759b41bd15b5f6ad958d17605 \ + --hash=sha256:9edbe6a5bf8b56a4a84533ba2b2f489d0046e755c29616ef8830f9e7d9cf5728 \ + --hash=sha256:a15c1fe6d26e83fd2e5972425a772cca158eae58b05d4a25a4e474c221053e2d \ + --hash=sha256:a66bcdf19c1a523e41b8e9d53d0cedbfbac2e93c649a2e9502cb26c014d0980c \ + --hash=sha256:ae4070f741f8d809075ef697877fd350ecf0b7c5837ed68738607ee0a2c572cf \ + --hash=sha256:ae55d592b02c4349525b6ed8f74c692509e5adffa842e582c0f861751701a673 \ + --hash=sha256:b578cbe580e3b41ad17b1c428f382c814b32a6ce90f2d8e39e2e635d49e498d1 \ + --hash=sha256:b891a2f68e09c5ef989007fac11476ed33c5c9994449a4e2c3386529d703dc8b \ + --hash=sha256:baec8148d6b8bd5cee1ae138ba658c71f5b03e0d69d5907703e3e1df96db5e41 \ + --hash=sha256:bb06098d019766ca16fc915ecaa455c1f1cd594204e7f840cd6258237b5079a8 \ + --hash=sha256:bc791ec3fd0c4309a753f95bb6c749ef0d8ea3aea91f07ee1cf06b7b02118f2f \ + --hash=sha256:bd28b31730f0e982ace8663d108e01199098432a30a4c410d06fe08fdb9e93f4 \ + --hash=sha256:be4d9c2770044a59715eb57c1144dedea7c5d5ae80c68fb9959515037cde2008 \ + --hash=sha256:c0c72d34e7de5604df0fde3644cc079feee5e55464967d10b24b1de268deceb9 \ + --hash=sha256:c0e842112fe3f1a4ffcf64b06dc4c61a88441c2f02f373367f7b4c1aa9be2ad5 \ + --hash=sha256:c15070ebf11b8b7fd1bfff7217e9324963c82dbdf6182ff7050519e350e7ad9f \ + --hash=sha256:c2000c54c395d9e5e44c99dc7c20a64dc371f777faf8bae4919ad3e99ce5253e \ + --hash=sha256:c30187840d36d0ba2893bc3271a36a517a717f9fd383a98e2697ee890a37c273 \ + --hash=sha256:cb7cd68814308aade9d0c93c5bd2ade9f9441666f8ba5aa9c2d4b389cb5e2a45 \ + --hash=sha256:cd805513198304026bd379d1d516afbf6c3c13f4382134a2c526b8b854da1c2e \ + --hash=sha256:d0bf89afcbcf4d1bb2652f6580e5e55a840fdf87384f6063c4a4f0c95e378656 \ + --hash=sha256:d9137a876020661972ca6eec0766d81aef8a5627df628b664b234b73396e727e \ + --hash=sha256:dbd95e300367aa0827496fe75a1766d198d34385a58f97683fe6e07f89ca3e3c \ + --hash=sha256:dced27917823df984fe0c80a5c4ad75cf58df0fbfae890bc08004cd3888922a2 \ + --hash=sha256:de0b4caa1c8a21394e8ce971997614a17648f94e1cd0640fbd6b4d14cab13a72 \ + --hash=sha256:debb633f3f7856f95ad957d9b9c781f8e2c6303ef21724ec94bea2ce2fcbd056 \ + --hash=sha256:e372d7dfd154009142631de2d316adad3cc1c36c32a38b16a4751ba78da2a397 \ + --hash=sha256:ecd26be9f112c4f96718290c10f4caea6cc798459a3a76636b817a0ed7874e42 \ + --hash=sha256:edc0202099ea1d82844316604e17d2b175044f9bcb6b398aab781eba957224bd \ + --hash=sha256:f194cce575e59ffe442c10a360182a986535fd90b57f7debfaa5c845c409ecc3 \ + --hash=sha256:f5fb672c396d826ca16a022ac04c9dce74e00a1c344f6ad1a0fdc1ba1f332213 \ + --hash=sha256:f6a02a3c7950cafaadcd46a226ad9e12fc9744652cc69f9e5534f98b47f3bbcf \ + --hash=sha256:fe81b35c33772e56f4b6cf62cf4aedc1762ef7162a31e6ac7fe5e40d0149eb67 # via requests click==8.1.7 \ --hash=sha256:ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28 \ --hash=sha256:ca9853ad459e787e2192211578cc907e7594e294c7ccc834310722b41b9ca6de # via # black + # maison # pip-tools # platformio # uvicorn + # yamlfix colorama==0.4.6 \ --hash=sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44 \ --hash=sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6 @@ -289,6 +291,10 @@ distlib==0.3.7 \ --hash=sha256:2e24928bc811348f0feb63014e97aaae3037f2cf48712d51ae61df7fd6075057 \ --hash=sha256:9dafe54b34a028eafd95039d5e5d4851a13734540f1331060d31c9916e7147a8 # via virtualenv +distro==1.8.0 \ + --hash=sha256:02e111d1dc6a50abb8eed6bf31c3e48ed8b0830d1ea2a1b78c61765c2513fdd8 \ + --hash=sha256:99522ca3e365cac527b44bde033f64c6945d90eb9f769703caaec52b09bbd3ff + # via ruyaml exceptiongroup==1.1.3 \ --hash=sha256:097acd85d473d75af5bb98e41b61ff7fe35efe6675e4f9370ec6ec5126d160e9 \ --hash=sha256:343280667a4585d195ca1cf9cef84a4e178c4b6cf2274caef9859782b567d5e3 @@ -471,6 +477,10 @@ linkify-it-py==2.0.2 \ --hash=sha256:19f3060727842c254c808e99d465c80c49d2c7306788140987a1a7a29b0d6ad2 \ --hash=sha256:a3a24428f6c96f27370d7fe61d2ac0be09017be5190d68d8658233171f1b6541 # via markdown-it-py +maison==1.4.0 \ + --hash=sha256:591a6ffe972558685cf2c3fdbff3dfa1e6b57a0227c50d387426ab9745e5939b \ + --hash=sha256:9843758d7772e0fc3ca93cf3abfdd39656f41bc75f026fd8bfb5a0ac17f27a7e + # via yamlfix markdown-it-py[linkify]==2.2.0 \ --hash=sha256:5a35f8d1870171d9acc47b99612dc146129b631baf04970128b568f190d0cc30 \ --hash=sha256:7c9a5e412688bc771c67432cbfebcdd686c93ce6484913dccf06cb5a0bea35a1 @@ -654,7 +664,9 @@ packaging==23.2 \ pathspec==0.11.2 \ --hash=sha256:1d6ed233af05e679efb96b1851550ea95bbb64b7c490b0f5aa52996c11e92a20 \ --hash=sha256:e0d8d0ac2f12da61956eb2306b69f9469b42f4deb0f3cb6ed47b9cce9996ced3 - # via black + # via + # black + # yamllint pillow==10.1.0 \ --hash=sha256:00f438bb841382b15d7deb9a05cc946ee0f2c352653c7aa659e75e592f6fa17d \ --hash=sha256:0248f86b3ea061e67817c47ecbe82c23f9dd5d5226200eb9090b3873d3ca32de \ @@ -729,6 +741,44 @@ pre-commit==3.5.0 \ --hash=sha256:5804465c675b659b0862f07907f96295d490822a450c4c40e747d0b1c6ebcb32 \ --hash=sha256:841dc9aef25daba9a0238cd27984041fa0467b4199fc4852e27950664919f660 # via selfdrive (pyproject.toml) +pydantic==1.10.13 \ + --hash=sha256:1740068fd8e2ef6eb27a20e5651df000978edce6da6803c2bef0bc74540f9548 \ + --hash=sha256:210ce042e8f6f7c01168b2d84d4c9eb2b009fe7bf572c2266e235edf14bacd80 \ + --hash=sha256:32c8b48dcd3b2ac4e78b0ba4af3a2c2eb6048cb75202f0ea7b34feb740efc340 \ + --hash=sha256:3ecea2b9d80e5333303eeb77e180b90e95eea8f765d08c3d278cd56b00345d01 \ + --hash=sha256:4b03e42ec20286f052490423682016fd80fda830d8e4119f8ab13ec7464c0132 \ + --hash=sha256:4c5370a7edaac06daee3af1c8b1192e305bc102abcbf2a92374b5bc793818599 \ + --hash=sha256:56e3ff861c3b9c6857579de282ce8baabf443f42ffba355bf070770ed63e11e1 \ + --hash=sha256:5a1f9f747851338933942db7af7b6ee8268568ef2ed86c4185c6ef4402e80ba8 \ + --hash=sha256:5e08865bc6464df8c7d61439ef4439829e3ab62ab1669cddea8dd00cd74b9ffe \ + --hash=sha256:61d9dce220447fb74f45e73d7ff3b530e25db30192ad8d425166d43c5deb6df0 \ + --hash=sha256:654db58ae399fe6434e55325a2c3e959836bd17a6f6a0b6ca8107ea0571d2e17 \ + --hash=sha256:678bcf5591b63cc917100dc50ab6caebe597ac67e8c9ccb75e698f66038ea953 \ + --hash=sha256:6cf25c1a65c27923a17b3da28a0bdb99f62ee04230c931d83e888012851f4e7f \ + --hash=sha256:75ac15385a3534d887a99c713aa3da88a30fbd6204a5cd0dc4dab3d770b9bd2f \ + --hash=sha256:75b297827b59bc229cac1a23a2f7a4ac0031068e5be0ce385be1462e7e17a35d \ + --hash=sha256:7d6f6e7305244bddb4414ba7094ce910560c907bdfa3501e9db1a7fd7eaea127 \ + --hash=sha256:84bafe2e60b5e78bc64a2941b4c071a4b7404c5c907f5f5a99b0139781e69ed8 \ + --hash=sha256:854223752ba81e3abf663d685f105c64150873cc6f5d0c01d3e3220bcff7d36f \ + --hash=sha256:8ae5dd6b721459bfa30805f4c25880e0dd78fc5b5879f9f7a692196ddcb5a580 \ + --hash=sha256:8ef467901d7a41fa0ca6db9ae3ec0021e3f657ce2c208e98cd511f3161c762c6 \ + --hash=sha256:968ac42970f57b8344ee08837b62f6ee6f53c33f603547a55571c954a4225691 \ + --hash=sha256:97cce3ae7341f7620a0ba5ef6cf043975cd9d2b81f3aa5f4ea37928269bc1b87 \ + --hash=sha256:9849f031cf8a2f0a928fe885e5a04b08006d6d41876b8bbd2fc68a18f9f2e3fd \ + --hash=sha256:9f00790179497767aae6bcdc36355792c79e7bbb20b145ff449700eb076c5f96 \ + --hash=sha256:b87326822e71bd5f313e7d3bfdc77ac3247035ac10b0c0618bd99dcf95b1e687 \ + --hash=sha256:b97c1fac8c49be29486df85968682b0afa77e1b809aff74b83081cc115e52f33 \ + --hash=sha256:bc0898c12f8e9c97f6cd44c0ed70d55749eaf783716896960b4ecce2edfd2d69 \ + --hash=sha256:c553f6a156deb868ba38a23cf0df886c63492e9257f60a79c0fd8e7173537653 \ + --hash=sha256:c636925f38b8db208e09d344c7aa4f29a86bb9947495dd6b6d376ad10334fb78 \ + --hash=sha256:c958d053453a1c4b1c2062b05cd42d9d5c8eb67537b8d5a7e3c3032943ecd261 \ + --hash=sha256:d3a3c792a58e1622667a2837512099eac62490cdfd63bd407993aaf200a4cf1f \ + --hash=sha256:e31647d85a2013d926ce60b84f9dd5300d44535a9941fe825dc349ae1f760df9 \ + --hash=sha256:e70ca129d2053fb8b728ee7d1af8e553a928d7e301a311094b8a0501adc8763d \ + --hash=sha256:efff03cc7a4f29d9009d1c96ceb1e7a70a65cfe86e89d34e4a5f2ab1e5693737 \ + --hash=sha256:f59ef915cac80275245824e9d771ee939133be38215555e9dc90c6cb148aaeb5 \ + --hash=sha256:f8e81fc5fb17dae698f52bdd1c4f18b6ca674d7068242b2aff075f588301bbb0 + # via maison pyelftools==0.29 \ --hash=sha256:519f38cf412f073b2d7393aa4682b0190fa901f7c3fa0bff2b82d537690c7fc1 \ --hash=sha256:ec761596aafa16e282a31de188737e5485552469ac63b60cfcccf22263fd24ff @@ -808,7 +858,9 @@ pyyaml==6.0.1 \ --hash=sha256:fca0e3a251908a499833aa292323f32437106001d436eca0e6e7833256674585 \ --hash=sha256:fd1592b3fdf65fff2ad0004b5e363300ef59ced41c2e6b3a99d4089fa8c5435d \ --hash=sha256:fd66fc5d0da6d9815ba2cebeb4205f95818ff4b79c3ebe268e75d961704af52f - # via pre-commit + # via + # pre-commit + # yamllint redis==5.0.1 \ --hash=sha256:0dab495cd5753069d3bc650a0dde8a8f9edde16fc5691b689a566eda58100d0f \ --hash=sha256:ed4802971884ae19d640775ba3b03aa2e7bd5e8fb8dfaed2decce4d0fc48391f @@ -836,6 +888,10 @@ ruff==0.1.1 \ --hash=sha256:e140bd717c49164c8feb4f65c644046fe929c46f42493672853e3213d7bdbce2 \ --hash=sha256:f4780e2bb52f3863a565ec3f699319d3493b83ff95ebbb4993e59c62aaf6e75e # via selfdrive (pyproject.toml) +ruyaml==0.91.0 \ + --hash=sha256:50e0ee3389c77ad340e209472e0effd41ae0275246df00cdad0a067532171755 \ + --hash=sha256:6ce9de9f4d082d696d3bde264664d1bcdca8f5a9dff9d1a1f1a127969ab871ab + # via yamlfix semantic-version==2.10.0 \ --hash=sha256:bdabb6d336998cbb378d4b9db3a4b56a1e3235701dc05ea2690d9a997ed5041c \ --hash=sha256:de78a3b8e0feda74cabc54aab2da702113e33ac9d9eb9d2389bcf1f58b7d9177 @@ -864,6 +920,10 @@ textparser==0.24.0 \ --hash=sha256:379d25cdb21332f403bfa37b9ef11192b7796340d2602d88fc9246bfdba2a1cf \ --hash=sha256:56f708e75aa9d002adb76d823ba6ef166d7ecec1e3e4ca4c1ca103f817568335 # via cantools +toml==0.10.2 \ + --hash=sha256:806143ae5bfb6a3c6e736a764057db0e6a0e05e338b5630894a5f779cabb4f9b \ + --hash=sha256:b3bda1d108d5dd99f4a20d24d9c348e91c4db7ab1b749200bded2f839ccbe68f + # via maison tomli==2.0.1 \ --hash=sha256:939de3e7a6161af0c887ef91b7d41a53e7c5a1ca976325f429cb46ea9bc30ecc \ --hash=sha256:de526c12914f0c550d15924c62d72abc48d6fe7364aa87328337a31007fe8a4f @@ -883,6 +943,7 @@ typing-extensions==4.8.0 \ # via # black # cantools + # pydantic # python-can # uvicorn uc-micro-py==1.0.2 \ @@ -986,11 +1047,19 @@ wsproto==1.2.0 \ --hash=sha256:ad565f26ecb92588a3e43bc3d96164de84cd9902482b130d0ddbaa9664a85065 \ --hash=sha256:b9acddd652b585d75b20477888c56642fdade28bdfd3579aa24a4d2c037dd736 # via platformio +yamlfix==1.15.0 \ + --hash=sha256:22095f0aaa9a6c07b279385b3b567b1553d6cb12d6f2c41dd2bb0a4361efc70d \ + --hash=sha256:6aa50eac3b308ef8d31f5e0d0c36aa5c5bd46de4d8f943ae6cb62df60e8e7e72 + # via selfdrive (pyproject.toml) +yamllint==1.32.0 \ + --hash=sha256:d01dde008c65de5b235188ab3110bebc59d18e5c65fc8a58267cd211cd9df34a \ + --hash=sha256:d97a66e48da820829d96077d76b8dfbe6c6140f106e558dae87e81ac4e6b30b7 + # via selfdrive (pyproject.toml) # The following packages are considered to be unsafe in a requirements file: -pip==23.3 \ - --hash=sha256:bb7d4f69f488432e4e96394612f43ab43dd478d073ef7422604a570f7157561e \ - --hash=sha256:bc38bb52bc286514f8f7cb3a1ba5ed100b76aaef29b521d48574329331c5ae7b +pip==23.3.1 \ + --hash=sha256:1fcaa041308d01f14575f6d0d2ea4b75a3e2871fe4f9c694976f908768e14174 \ + --hash=sha256:55eb67bb6171d37447e82213be585b75fe2b12b359e993773aca4de9247a052b # via pip-tools setuptools==68.2.2 \ --hash=sha256:4ac1475276d2f1c48684874089fefcd83bd7162ddaafb81fac866ba0db282a87 \ @@ -999,3 +1068,4 @@ setuptools==68.2.2 \ # nodeenv # pip-tools # python-can + # ruyaml diff --git a/ros/docker-compose.yml b/ros/docker-compose.yml index 28b5fe98b..9cad6dcce 100644 --- a/ros/docker-compose.yml +++ b/ros/docker-compose.yml @@ -1,214 +1,220 @@ +--- + # https://docs.docker.com/compose/gpu-support/ version: '3' services: - master: - build: docker/master/. - container_name: master - tty: true - environment: - - 'ROS_HOSTNAME=master' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - ports: - - '11311:11311' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - restart: unless-stopped - command: stdbuf -o L roscore + master: + build: docker/master/. + container_name: master + tty: true + environment: + - ROS_HOSTNAME=master + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + ports: + - 11311:11311 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + restart: unless-stopped + command: stdbuf -o L roscore - redis: - image: redis:7.0-alpine - container_name: redis - restart: unless-stopped - ports: - - '6379:6379' + redis: + image: redis:7.0-alpine + container_name: redis + restart: unless-stopped + ports: + - 6379:6379 - pure_pursuit: - build: docker/pure_pursuit/. - container_name: pure_pursuit - tty: true - environment: - - 'ROS_HOSTNAME=pure_pursuit' - - 'ROS_MASTER_URI=http://master:11311' - volumes: - - './docker/pure_pursuit:/app/ros_ws/src/pure_pursuit' - depends_on: - - master + pure_pursuit: + build: docker/pure_pursuit/. + container_name: pure_pursuit + tty: true + environment: + - ROS_HOSTNAME=pure_pursuit + - ROS_MASTER_URI=http://master:11311 + volumes: + - ./docker/pure_pursuit:/app/ros_ws/src/pure_pursuit + depends_on: + - master - navigation: - build: docker/navigation/. - container_name: navigation - tty: true - environment: - - 'ROS_HOSTNAME=navigation' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - - './docker/navigation/scooter_launch:/app/ros_ws/src/scooter_launch' + navigation: + build: docker/navigation/. + container_name: navigation + tty: true + environment: + - ROS_HOSTNAME=navigation + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + - ./docker/navigation/scooter_launch:/app/ros_ws/src/scooter_launch - velodyne: - build: docker/velodyne/. - container_name: velodyne - tty: true - environment: - - 'ROS_HOSTNAME=velodyne' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - - './docker/velodyne/velodyne_launch:/app/ros_ws/src/velodyne_launch' - depends_on: - - master - ports: - - 2368:2368/udp - - 8308:8308/udp + velodyne: + build: docker/velodyne/. + container_name: velodyne + tty: true + environment: + - ROS_HOSTNAME=velodyne + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + - ./docker/velodyne/velodyne_launch:/app/ros_ws/src/velodyne_launch + depends_on: + - master + ports: + - 2368:2368/udp + - 8308:8308/udp - zed: - build: docker/zed/. - #image: git-registry.cooperigvc.org/igvc/selfdrive/ros/zed:0.1 - container_name: zed - tty: true - privileged: true - environment: - - 'ROS_HOSTNAME=zed' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/dev:/dev' # Come up with a better solution later. Maybe mount the file associated with the zed only - - '/tmp/.X11-unix:/tmp/.X11-unix' - - './docker/zed/zed_launch:/app/ros_ws/src/zed_launch' - # depends_on: - # - master - deploy: - resources: - reservations: - devices: - - capabilities: [gpu] - restart: unless-stopped + zed: + build: docker/zed/. + container_name: zed + tty: true + privileged: true + environment: + - ROS_HOSTNAME=zed + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + # Come up with a better solution later. Maybe mount the file + # associated with the zed only + - /dev:/dev + - /tmp/.X11-unix:/tmp/.X11-unix + - ./docker/zed/zed_launch:/app/ros_ws/src/zed_launch + # depends_on: + # - master + deploy: + resources: + reservations: + devices: + - capabilities: + - gpu + restart: unless-stopped - imu: - build: docker/yost_imu/. - container_name: imu - tty: true - privileged: true - environment: - - 'ROS_HOSTNAME=imu' - - 'ROS_MASTER_URI=http://master:11311' - volumes: - - '/dev:/dev' # Come up with a better solution later. Maybe mount the file associated with the zed only - - '/tmp/.X11-unix:/tmp/.X11-unix' + imu: + build: docker/yost_imu/. + container_name: imu + tty: true + privileged: true + environment: + - ROS_HOSTNAME=imu + - ROS_MASTER_URI=http://master:11311 + volumes: + # Come up with a better solution later. Maybe mount the file + # associated with the zed only + - /dev:/dev + - /tmp/.X11-unix:/tmp/.X11-unix - rviz: - build: docker/rviz/. - container_name: rviz - tty: true - environment: - - 'ROS_HOSTNAME=rviz' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - depends_on: - - master + rviz: + build: docker/rviz/. + container_name: rviz + tty: true + environment: + - ROS_HOSTNAME=rviz + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + depends_on: + - master - rtabmap: - build: docker/rtabmap/. - container_name: rtabmap - tty: true - privileged: true - environment: - - 'ROS_HOSTNAME=rtabmap' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - #- ~/.ros:/root - - '/home/eeadmin/comp-data:/comp-data' - - './docker/rtabmap/rtabmap_launch:/app/ros_ws/src/rtabmap_launch' - depends_on: - - master - deploy: - resources: - reservations: - devices: - - capabilities: [gpu] + rtabmap: + build: docker/rtabmap/. + container_name: rtabmap + tty: true + privileged: true + environment: + - ROS_HOSTNAME=rtabmap + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + # - ~/.ros:/root + - /home/eeadmin/comp-data:/comp-data + - ./docker/rtabmap/rtabmap_launch:/app/ros_ws/src/rtabmap_launch + depends_on: + - master + deploy: + resources: + reservations: + devices: + - capabilities: + - gpu - gps: - build: docker/gps/. - container_name: gps - tty: true - privileged: true - environment: - - 'ROS_HOSTNAME=gps' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - depends_on: - - master + gps: + build: docker/gps/. + container_name: gps + tty: true + privileged: true + environment: + - ROS_HOSTNAME=gps + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + depends_on: + - master - encoder_odom: - build: docker/encoder_odom - container_name: encoder_odom - tty: true - environment: - - 'ROS_HOSTNAME=encoder_odom' - - 'ROS_MASTER_URI=http://master:11311' - volumes: - - './docker/encoder_odom/src:/app/ros_ws/src/encoder_odom' - depends_on: - - master + encoder_odom: + build: docker/encoder_odom + container_name: encoder_odom + tty: true + environment: + - ROS_HOSTNAME=encoder_odom + - ROS_MASTER_URI=http://master:11311 + volumes: + - ./docker/encoder_odom/src:/app/ros_ws/src/encoder_odom + depends_on: + - master - techbus: - build: docker/techbus/ - container_name: techbus - tty: true - environment: - - 'ROS_HOSTNAME=techbus' - - 'ROS_MASTER_URI=http://master:11311' - volumes: - - './docker/techbus:/app/ros_ws/src/techbus' - depends_on: - - master + techbus: + build: docker/techbus/ + container_name: techbus + tty: true + environment: + - ROS_HOSTNAME=techbus + - ROS_MASTER_URI=http://master:11311 + volumes: + - ./docker/techbus:/app/ros_ws/src/techbus + depends_on: + - master - detection: - build: docker/detection/ - container_name: detection - tty: true - environment: - - 'ROS_HOSTNAME=detection' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - - './docker/detection:/app/ros_ws/src/detection' - depends_on: - - master + detection: + build: docker/detection/ + container_name: detection + tty: true + environment: + - ROS_HOSTNAME=detection + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + - ./docker/detection:/app/ros_ws/src/detection + depends_on: + - master - gazebo: - build: docker/gazebo/. - container_name: gazebo - tty: true - privileged: true - environment: - - 'ROS_HOSTNAME=gazebo' - - 'ROS_MASTER_URI=http://master:11311' - - 'DISPLAY=$DISPLAY' - - 'QT_X11_NO_MITSHM=1' - volumes: - - '/tmp/.X11-unix:/tmp/.X11-unix' - - './docker/gazebo/igvc_self_drive_sim:/app/ros_ws/src/igvc_self_drive_sim' - depends_on: - - master - restart: unless-stopped - - master + gazebo: + build: docker/gazebo/. + container_name: gazebo + tty: true + privileged: true + environment: + - ROS_HOSTNAME=gazebo + - ROS_MASTER_URI=http://master:11311 + - DISPLAY=$DISPLAY + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + - ./docker/gazebo/igvc_self_drive_sim:/app/ros_ws/src/igvc_self_drive_sim + depends_on: + - master + restart: unless-stopped - master diff --git a/ros/docker/gazebo/igvc_self_drive_sim/.travis.yml b/ros/docker/gazebo/igvc_self_drive_sim/.travis.yml index d31c597e6..e83224532 100644 --- a/ros/docker/gazebo/igvc_self_drive_sim/.travis.yml +++ b/ros/docker/gazebo/igvc_self_drive_sim/.travis.yml @@ -1,16 +1,23 @@ +--- + sudo: required dist: trusty language: generic + branches: except: - - noetic-devel + - noetic-devel + env: global: - ROS_PARALLEL_TEST_JOBS=-j1 matrix: - ROS_DISTRO="kinetic" ROS_REPO=ros - ROS_DISTRO="melodic" ROS_REPO=ros + install: + # yamllint disable-line rule:line-length - git clone --depth 1 https://github.com/ros-industrial/industrial_ci.git .industrial_ci + script: - .industrial_ci/ci.sh diff --git a/ros/docker/navigation/scooter_launch/maps/blank_map.yaml b/ros/docker/navigation/scooter_launch/maps/blank_map.yaml index 5da5fb866..d16f63a57 100644 --- a/ros/docker/navigation/scooter_launch/maps/blank_map.yaml +++ b/ros/docker/navigation/scooter_launch/maps/blank_map.yaml @@ -1,6 +1,14 @@ +--- + image: blank_map.pgm resolution: 0.01 -origin: [-2.5, -2.5, 0] + +origin: + - -2.5 + - -2.5 + - 0 + occupied_thresh: 0.65 -free_thresh: 0.195 # Taken from the Willow Garage map in the turtlebot_navigation package +# Taken from the Willow Garage map in the turtlebot_navigation package +free_thresh: 0.195 negate: 0 diff --git a/ros/docker/navigation/scooter_launch/maps/my_map.yaml b/ros/docker/navigation/scooter_launch/maps/my_map.yaml index d1f19efe7..6814bba4f 100644 --- a/ros/docker/navigation/scooter_launch/maps/my_map.yaml +++ b/ros/docker/navigation/scooter_launch/maps/my_map.yaml @@ -1,6 +1,12 @@ +--- image: my_map.pgm resolution: 0.100000 -origin: [0.000000, 0.000000, 0.000000] + +origin: + - 0.000000 + - 0.000000 + - 0.000000 + negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 diff --git a/ros/docker/navigation/scooter_launch/param/base_local_planner_params.yaml b/ros/docker/navigation/scooter_launch/param/base_local_planner_params.yaml index 5d9d1c743..b52748f5f 100644 --- a/ros/docker/navigation/scooter_launch/param/base_local_planner_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/base_local_planner_params.yaml @@ -1,27 +1,29 @@ +--- + TrajectoryPlannerROS: -# Robot Configuration Parameters + # Robot Configuration Parameters max_vel_x: 1.0 min_vel_x: 0.95 - max_vel_theta: 0.2 + max_vel_theta: 0.2 min_vel_theta: -0.2 min_in_place_vel_theta: 1000.0 acc_lim_x: 0.5 acc_lim_theta: 1.0 -# Goal Tolerance Parameters + # Goal Tolerance Parameters yaw_goal_tolerance: 0.15 xy_goal_tolerance: 0.20 -# Forward Simulation Parameters + # Forward Simulation Parameters sim_time: 6.0 vx_samples: 8 vtheta_samples: 20 controller_frequency: 20.0 -# Trajectory Scoring Parameters + # Trajectory Scoring Parameters meter_scoring: true pdist_scale: 5.0 gdist_s6ale: 2.0 @@ -29,10 +31,10 @@ TrajectoryPlannerROS: heading_lookahead: 0.325 dwa: false -# Oscillation Prevention Parameters + # Oscillation Prevention Parameters oscillation_reset_dist: 0.05 -# Differential-drive robot configuration + # Differential-drive robot configuration holonomic_robot: false max_vel_y: 0.0 min_vel_y: 0.0 diff --git a/ros/docker/navigation/scooter_launch/param/costmap_common_params.yaml b/ros/docker/navigation/scooter_launch/param/costmap_common_params.yaml index 779a79aeb..3717be253 100644 --- a/ros/docker/navigation/scooter_launch/param/costmap_common_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/costmap_common_params.yaml @@ -1,21 +1,31 @@ -# max_obstacle_height: 0.60 # assume something like an arm is mounted on top of the robot +--- + +# assume something like an arm is mounted on top of the robot +# max_obstacle_height: 0.60 # Obstacle Cost Shaping (http://wiki.ros.org/costmap_2d/hydro/inflation) -#robot_radius: 5.0 # distance a circular robot should be clear of the obstacle (kobuki: 0.18) -footprint: [[0, -1], [0, 1], [3.2, -1], [3.2, 1]] # if the robot is not circular +# distance a circular robot should be clear of the obstacle (kobuki: 0.18) +# robot_radius: 5.0 +footprint: # if the robot is not circular + - [0, -1] + - [0, 1] + - [3.2, -1] + - [3.2, 1] map_type: voxel virtual_layer: - enabled: true - zone_topics: [/virtual_costmap_layer/zone] - obstacle_topics: [/virtual_costmap_layer/obstacles] - one_zone: true + enabled: true + zone_topics: + - /virtual_costmap_layer/zone + obstacle_topics: + - /virtual_costmap_layer/obstacles + one_zone: true forms: - - [0.4, 0.0] - - [[0.4, 0.0]] - - [[-0.4, 0.0],[0.0, 0.4]] - - [[100, 100],[-100, 100],[-100, -100],[100, -100]] + - [0.4, 0.0] + - [[0.4, 0.0]] + - [[-0.4, 0.0], [0.0, 0.4]] + - [[100, 100], [-100, 100], [-100, -100], [100, -100]] # obstacle_layer: # enabled: true @@ -49,8 +59,12 @@ virtual_layer: # max_obstacle_height: 0.15 # # for debugging only, let's you see the entire voxel grid -# #cost_scaling_factor and inflation_radius were now moved to the inflation_layer ns +# cost_scaling_factor and inflation_radius were now moved to the +# inflation_layer ns # inflation_layer: # enabled: true -# cost_scaling_factor: 3.0 # exponential rate at which the obstacle cost drops off (default: 10) -# inflation_radius: 1.0 # max. distance from an obstacle at which costs are incurred for planning paths. +# # exponential rate at which the obstacle cost drops off (default: 10) +# cost_scaling_factor: 3.0 +# # max. distance from an obstacle at which costs are incurred for +# # planning paths. +# inflation_radius: 1.0 diff --git a/ros/docker/navigation/scooter_launch/param/dwa_local_planner_params.yaml b/ros/docker/navigation/scooter_launch/param/dwa_local_planner_params.yaml index 0a896b23d..1485fba25 100644 --- a/ros/docker/navigation/scooter_launch/param/dwa_local_planner_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/dwa_local_planner_params.yaml @@ -1,58 +1,65 @@ +--- + +# yamllint disable rule:line-length DWAPlannerROS: -# Robot Configuration Parameters - Kobuki - max_vel_x: 0.55 #abs max 0.7 #0.5 # 0.55 - min_vel_x: 0.0 + # Robot Configuration Parameters - Kobuki + max_vel_x: 0.55 # abs max 0.7 # 0.5 # 0.55 + min_vel_x: 0.0 - max_vel_y: 0.0 # diff drive robot - min_vel_y: 0.0 # diff drive robot + max_vel_y: 0.0 # diff drive robot + min_vel_y: 0.0 # diff drive robot - max_vel_trans: 0.5 # choose slightly less than the base's capability - min_vel_trans: 0.1 # this is the min trans velocity when there is negligible rotational velocity - trans_stopped_vel: 0.1 + max_vel_trans: 0.5 # choose slightly less than the base's capability + min_vel_trans: 0.1 # this is the min trans velocity when there is negligible rotational velocity + trans_stopped_vel: 0.1 - # Warning! - # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities - # are non-negligible and small in place rotational velocities will be created. + # Warning! + # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities + # are non-negligible and small in place rotational velocities will be created. - max_rot_vel: 3.14 #5.0 # choose slightly less than the base's capability - min_rot_vel: 0.4 # this is the min angular velocity when there is negligible translational velocity - rot_stopped_vel: 0.4 + max_rot_vel: 3.14 # 5.0 # choose slightly less than the base's capability + min_rot_vel: 0.4 # this is the min angular velocity when there is negligible translational velocity + rot_stopped_vel: 0.4 - acc_lim_x: 1.0 # maximum is theoretically 2.0, but we - acc_lim_theta: 2.0 - acc_lim_y: 0.0 # diff drive robot + acc_lim_x: 1.0 # maximum is theoretically 2.0, but we + acc_lim_theta: 2.0 + acc_lim_y: 0.0 # diff drive robot -# Goal Tolerance Parameters - yaw_goal_tolerance: 0.05 # 0.05 - xy_goal_tolerance: 0.10 # 0.10 - latch_xy_goal_tolerance: false + # Goal Tolerance Parameters + yaw_goal_tolerance: 0.05 # 0.05 + xy_goal_tolerance: 0.10 # 0.10 + latch_xy_goal_tolerance: false -# Forward Simulation Parameters - sim_time: 1.7 # 1.7 - vx_samples: 6 # 3 - vy_samples: 1 # diff drive robot, there is only one sample - vth_samples: 20 # 20 - sim_granularity: 0.1 + # Forward Simulation Parameters + sim_time: 1.7 # 1.7 + vx_samples: 6 # 3 + vy_samples: 1 # diff drive robot, there is only one sample + vth_samples: 20 # 20 + sim_granularity: 0.1 -# Trajectory Scoring Parameters - path_distance_bias: 32 # 32.0 - weighting for how much it should stick to the global path plan - goal_distance_bias: 24 # 24.0 - wighting for how much it should attempt to reach its goal - occdist_scale: 0.01 # 0.01 - weighting for how much the controller should avoid obstacles - forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point - stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj. - scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint - max_scaling_factor: 0.2 # 0.2 - how much to scale the robot's footprint when at speed. + # yamllint disable rule:line-length + # Trajectory Scoring Parameters + path_distance_bias: 32 # 32.0 - weighting for how much it should stick to the global path plan + goal_distance_bias: 24 # 24.0 - wighting for how much it should attempt to reach its goal + occdist_scale: 0.01 # 0.01 - weighting for how much the controller should avoid obstacles + forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point + stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj. + scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint + max_scaling_factor: 0.2 # 0.2 - how much to scale the robot's footprint when at speed. + # yamllint enable rule:line-length -# Oscillation Prevention Parameters - oscillation_reset_dist: 0.05234324324324 # 0.05 - how far to travel before resetting oscillation flags + # Oscillation Prevention Parameters + # 0.05 - how far to travel before resetting oscillation flags + oscillation_reset_dist: 0.05234324324324 -# Debugging - publish_traj_pc : true - publish_cost_grid_pc: true - global_frame_id: odom + # Debugging + publish_traj_pc: true + publish_cost_grid_pc: true + global_frame_id: odom - prune_plan: true + prune_plan: true # Differential-drive robot configuration - necessary? holonomic_robot: false +# yamllint enable rule:line-length diff --git a/ros/docker/navigation/scooter_launch/param/global_costmap_params.yaml b/ros/docker/navigation/scooter_launch/param/global_costmap_params.yaml index e1ba30fcf..e13f7e5df 100644 --- a/ros/docker/navigation/scooter_launch/param/global_costmap_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/global_costmap_params.yaml @@ -1,3 +1,5 @@ +--- + global_costmap: # Costmap_2d parameters global_frame: map @@ -9,11 +11,14 @@ global_costmap: width: 100 height: 100 plugins: - - {name: static_layer, type: "costmap_2d::StaticLayer"} - - {name: obstacle_layer, type: "costmap_2d::VoxelLayer"} - - { name: virtual_layer, type: "virtual_costmap_layer::VirtualLayer"} - - {name: inflation_layer, type: "costmap_2d::InflationLayer"} - + - name: static_layer + type: costmap_2d::StaticLayer + - name: obstacle_layer + type: costmap_2d::VoxelLayer + - name: virtual_layer + type: virtual_costmap_layer::VirtualLayer + - name: inflation_layer + type: costmap_2d::InflationLayer static_layer: enabled: true @@ -29,7 +34,7 @@ global_costmap: obstacle_layer: enabled: true # combination_method: 1 Used for ObstacleCostmapPlugin - track_unknown_space: false + track_unknown_space: false # Global Parameters applied to all sensors max_obstacle_height: 1.8 obstacle_range: 2.5 @@ -42,13 +47,14 @@ global_costmap: mark_threshold: 0 footprint_clearing_enabled: true observation_sources: rtabmap # scan - # scan: - # data_type: LaserScan - # topic: /scan_filtered - # marking: true # Only used by local costmap - # clearing: true # Has to free up space for local planner is path is avalible - # min_obstacle_height: 0.0 - # max_obstacle_height: 2.0 + # scan: + # data_type: LaserScan + # topic: /scan_filtered + # marking: true # Only used by local costmap + # # Has to free up space for local planner is path is avalible + # clearing: true + # min_obstacle_height: 0.0 + # max_obstacle_height: 2.0 rtabmap: data_type: PointCloud2 topic: /rtabmap/cloud_map @@ -58,6 +64,6 @@ global_costmap: max_obstacle_height: 2.0 inflation_layer: - enabled: true - inflation_radius: 0.3 - cost_scaling_factor: 0.5 + enabled: true + inflation_radius: 0.3 + cost_scaling_factor: 0.5 diff --git a/ros/docker/navigation/scooter_launch/param/global_planner_params.yaml b/ros/docker/navigation/scooter_launch/param/global_planner_params.yaml index 9e572f8c5..2a2b72507 100644 --- a/ros/docker/navigation/scooter_launch/param/global_planner_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/global_planner_params.yaml @@ -1,23 +1,26 @@ +--- -GlobalPlanner: # Also see: http://wiki.ros.org/global_planner - old_navfn_behavior: false # Exactly mirror behavior of navfn, use defaults for other boolean parameters, default false - use_quadratic: true # Use the quadratic approximation of the potential. Otherwise, use a simpler calculation, default true - use_dijkstra: true # Use dijkstra's algorithm. Otherwise, A*, default true - use_grid_path: false # Create a path that follows the grid boundaries. Otherwise, use a gradient descent method, default false +# yamllint disable rule:line-length +GlobalPlanner: # Also see: http://wiki.ros.org/global_planner + old_navfn_behavior: false # Exactly mirror behavior of navfn, use defaults for other boolean parameters, default false + use_quadratic: true # Use the quadratic approximation of the potential. Otherwise, use a simpler calculation, default true + use_dijkstra: true # Use dijkstra's algorithm. Otherwise, A*, default true + use_grid_path: false # Create a path that follows the grid boundaries. Otherwise, use a gradient descent method, default false - visualize_potential: true # For visulization in RVIZ + visualize_potential: true # For visulization in RVIZ - allow_unknown: true # Allow planner to plan through unknown space, default true - #Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work - planner_window_x: 0.0 # default 0.0 - planner_window_y: 0.0 # default 0.0 - default_tolerance: 0.0 # If goal in obstacle, plan to the closest point in radius default_tolerance, default 0.0 + allow_unknown: true # Allow planner to plan through unknown space, default true + # Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work + planner_window_x: 0.0 # default 0.0 + planner_window_y: 0.0 # default 0.0 + default_tolerance: 0.0 # If goal in obstacle, plan to the closest point in radius default_tolerance, default 0.0 - publish_scale: 100 # Scale by which the published potential gets multiplied, default 100 - planner_costmap_publish_frequency: 1.0 # default 0.0 + publish_scale: 100 # Scale by which the published potential gets multiplied, default 100 + planner_costmap_publish_frequency: 1.0 # default 0.0 - lethal_cost: 253 # default 253 - neutral_cost: 66 # default 50 - cost_factor: 0.55 # Factor to multiply each cost from costmap by, default 3.0 - publish_potential: true # Publish Potential Costmap (this is not like the navfn pointcloud2 potential), default true + lethal_cost: 253 # default 253 + neutral_cost: 66 # default 50 + cost_factor: 0.55 # Factor to multiply each cost from costmap by, default 3.0 + publish_potential: true # Publish Potential Costmap (this is not like the navfn pointcloud2 potential), default true planner_frequency: 0.2 +# yamllint enable rule:line-length diff --git a/ros/docker/navigation/scooter_launch/param/local_costmap_params.yaml b/ros/docker/navigation/scooter_launch/param/local_costmap_params.yaml index c3f6f3f1a..bef73f4b3 100644 --- a/ros/docker/navigation/scooter_launch/param/local_costmap_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/local_costmap_params.yaml @@ -1,3 +1,4 @@ +--- local_costmap: # Costmap_2d parameters global_frame: map @@ -9,11 +10,14 @@ local_costmap: width: 100 height: 100 plugins: - - {name: static_layer, type: "costmap_2d::StaticLayer"} - - {name: obstacle_layer, type: "costmap_2d::VoxelLayer"} - - { name: virtual_layer, type: "virtual_costmap_layer::VirtualLayer"} - - {name: inflation_layer, type: "costmap_2d::InflationLayer"} - + - name: static_layer + type: costmap_2d::StaticLayer + - name: obstacle_layer + type: costmap_2d::VoxelLayer + - name: virtual_layer + type: virtual_costmap_layer::VirtualLayer + - name: inflation_layer + type: costmap_2d::InflationLayer static_layer: enabled: true @@ -29,7 +33,7 @@ local_costmap: obstacle_layer: enabled: true # combination_method: 1 Used for ObstacleCostmapPlugin - track_unknown_space: false + track_unknown_space: false # Global Parameters applied to all sensors max_obstacle_height: 1.8 obstacle_range: 2.5 @@ -42,13 +46,14 @@ local_costmap: mark_threshold: 0 footprint_clearing_enabled: true observation_sources: rtabmap # scan - # scan: - # data_type: LaserScan - # topic: /scan_filtered - # marking: true # Only used by local costmap - # clearing: true # Has to free up space for local planner is path is avalible - # min_obstacle_height: 0.0 - # max_obstacle_height: 2.0 + # scan: + # data_type: LaserScan + # topic: /scan_filtered + # marking: true # Only used by local costmap + # # Has to free up space for local planner is path is avalible + # clearing: true + # min_obstacle_height: 0.0 + # max_obstacle_height: 2.0 rtabmap: data_type: PointCloud2 topic: /rtabmap/cloud_map @@ -58,6 +63,6 @@ local_costmap: max_obstacle_height: 2.0 inflation_layer: - enabled: true - inflation_radius: 0.3 - cost_scaling_factor: 0.5 + enabled: true + inflation_radius: 0.3 + cost_scaling_factor: 0.5 diff --git a/ros/docker/navigation/scooter_launch/param/move_base_params.yaml b/ros/docker/navigation/scooter_launch/param/move_base_params.yaml index f4d408876..c810af85b 100644 --- a/ros/docker/navigation/scooter_launch/param/move_base_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/move_base_params.yaml @@ -1,3 +1,6 @@ +--- + +# yamllint disable rule:comments rule:comments-indentation rule:line-length # Move base node parameters. For full documentation of the parameters in this file, please see # # http://www.ros.org/wiki/move_base @@ -7,7 +10,6 @@ shutdown_costmaps: false # controller_frequency: 5.0 # controller_patience: 3.0 - planner_frequency: 1.0 planner_patience: 5.0 @@ -17,42 +19,48 @@ oscillation_distance: 0.2 # local planner - default is trajectory rollout # base_local_planner: "teb_local_planner/TebLocalPlannerROS" # base_local_planner: "dwa_local_planner/DWAPlannerROS" -base_local_planner: "base_local_planner/TrajectoryPlannerROS" - -base_global_planner: "navfn/NavfnROS" #alternatives: global_planner/GlobalPlanner, carrot_planner/CarrotPlanner +base_local_planner: base_local_planner/TrajectoryPlannerROS +base_global_planner: navfn/NavfnROS # alternatives: global_planner/GlobalPlanner, carrot_planner/CarrotPlanner -#We plan to integrate recovery behaviors for turtlebot but currently those belong to gopher and still have to be adapted. +# We plan to integrate recovery behaviors for turtlebot but currently those belong to gopher and still have to be adapted. ## recovery behaviors; we avoid spinning, but we need a fall-back replanning recovery_behavior_enabled: false -#recovery_behaviors: +# recovery_behaviors: #- name: 'super_conservative_reset1' - #type: 'clear_costmap_recovery/ClearCostmapRecovery' + # type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'conservative_reset1' - #type: 'clear_costmap_recovery/ClearCostmapRecovery' + # type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'aggressive_reset1' - #type: 'clear_costmap_recovery/ClearCostmapRecovery' + # type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'clearing_rotation1' - #type: 'rotate_recovery/RotateRecovery' + # type: 'rotate_recovery/RotateRecovery' #- name: 'super_conservative_reset2' - #type: 'clear_costmap_recovery/ClearCostmapRecovery' + # type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'conservative_reset2' - #type: 'clear_costmap_recovery/ClearCostmapRecovery' + # type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'aggressive_reset2' - #type: 'clear_costmap_recovery/ClearCostmapRecovery' + # type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'clearing_rotation2' - #type: 'rotate_recovery/RotateRecovery' - -#super_conservative_reset1: - #reset_distance: 3.0 -#conservative_reset1: - #reset_distance: 1.5 -#aggressive_reset1: - #reset_distance: 0.0 -#super_conservative_reset2: - #reset_distance: 3.0 -#conservative_reset2: - #reset_distance: 1.5 -#aggressive_reset2: - #reset_distance: 0.0 + # type: 'rotate_recovery/RotateRecovery' + +# super_conservative_reset1: + # reset_distance: 3.0 + +# conservative_reset1: + # reset_distance: 1.5 + +# aggressive_reset1: + # reset_distance: 0.0 + +# super_conservative_reset2: + # reset_distance: 3.0 + +# conservative_reset2: + # reset_distance: 1.5 + +# aggressive_reset2: + # reset_distance: 0.0 + +# yamllint enable rule:comments rule:comments-indentation rule:line-length diff --git a/ros/docker/navigation/scooter_launch/param/navfn_global_planner_params.yaml b/ros/docker/navigation/scooter_launch/param/navfn_global_planner_params.yaml index 188b409f1..fe09a2bdb 100644 --- a/ros/docker/navigation/scooter_launch/param/navfn_global_planner_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/navfn_global_planner_params.yaml @@ -1,10 +1,14 @@ +--- +# yamllint disable rule:line-length NavfnROS: - visualize_potential: false #Publish potential for rviz as pointcloud2, not really helpful, default false - allow_unknown: false #Specifies whether or not to allow navfn to create plans that traverse unknown space, default true - #Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work - planner_window_x: 0.0 #Specifies the x size of an optional window to restrict the planner to, default 0.0 - planner_window_y: 0.0 #Specifies the y size of an optional window to restrict the planner to, default 0.0 + visualize_potential: false # Publish potential for rviz as pointcloud2, not really helpful, default false + allow_unknown: false # Specifies whether or not to allow navfn to create plans that traverse unknown space, default true + # Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work + planner_window_x: 0.0 # Specifies the x size of an optional window to restrict the planner to, default 0.0 + planner_window_y: 0.0 # Specifies the y size of an optional window to restrict the planner to, default 0.0 - default_tolerance: 0.0 #If the goal is in an obstacle, the planer will plan to the nearest point in the radius of default_tolerance, default 0.0 - #The area is always searched, so could be slow for big values + default_tolerance: 0.0 # If the goal is in an obstacle, the planer will plan to the nearest point in the radius of default_tolerance, default 0.0 + # The area is always searched, so could be slow for big values + +# yamllint enable rule:line-length diff --git a/ros/docker/navigation/scooter_launch/param/r200_costmap_params.yaml b/ros/docker/navigation/scooter_launch/param/r200_costmap_params.yaml index b245898bd..5495054e2 100644 --- a/ros/docker/navigation/scooter_launch/param/r200_costmap_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/r200_costmap_params.yaml @@ -1,3 +1,6 @@ +--- + +# yamllint disable rule:line-length global_costmap: robot_radius: 0.20 # distance a circular robot should be clear of the obstacle (kobuki: 0.18) obstacle_layer: @@ -6,7 +9,7 @@ global_costmap: topic: scan marking: true clearing: true - min_obstacle_height: 0.05 # previous: 0.25, too high for the R200 configuration! + min_obstacle_height: 0.05 # previous: 0.25, too high for the R200 configuration! max_obstacle_height: 0.35 local_costmap: @@ -17,5 +20,7 @@ local_costmap: topic: scan marking: true clearing: true - min_obstacle_height: 0.05 # previous: 0.25, too high for the R200 configuration! + min_obstacle_height: 0.05 # previous: 0.25, too high for the R200 configuration! max_obstacle_height: 0.35 + +# yamllint enable rule:line-length diff --git a/ros/docker/navigation/scooter_launch/param/teb_local_planner_params.yaml b/ros/docker/navigation/scooter_launch/param/teb_local_planner_params.yaml index 82c1e11d2..49dd14083 100644 --- a/ros/docker/navigation/scooter_launch/param/teb_local_planner_params.yaml +++ b/ros/docker/navigation/scooter_launch/param/teb_local_planner_params.yaml @@ -1,78 +1,80 @@ +--- +# yamllint disable rule:line-length TebLocalPlannerRos: -# Robot Configuration Parameters - Scooter + # Robot Configuration Parameters - Scooter # All default values for teb-acc acc_lim_x: 20.0 acc_lim_theta: 20.0 max_vel_x: 2.2 - max_vel_x_backwards: 0.0 # Picked half foward vel + max_vel_x_backwards: 0.0 # Picked half foward vel max_vel_theta: 2.0 # Parameters for car like robots - For scooter but unecessary for simulations - min_turning_radius: 4.0 #0.85 # Measured value - wheelbase: 1.8 # Measured value + min_turning_radius: 4.0 # 0.85 # Measured value + wheelbase: 1.8 # Measured value cmd_angle_instead_rotvel: true -# Goal Tolerance Parameters + # Goal Tolerance Parameters # All default values for teb-tolerance yaw_goal_tolerance: 0.2 xy_goal_tolerance: 0.2 - free_goal_vel: false # Allows the scooter to reach goal at max speed + free_goal_vel: false # Allows the scooter to reach goal at max speed -# Trajectory Configuration Parameters - dt_ref: 0.3 # Desired temporal resolution - dt_hysteresis: 0.1 # Hysteresis for automatic resizing depending on the current temporal resolution Says recommended value is 10% of dt_ref but default is 0.1 - min_samples: 3 # Should always be greater than 2 - global_plan_overwrite_orientation: true # Overwrite orientation of local subgoals provided by global planner - global_plan_viapoint_sep: -0.1 # If positive: viapoints are extracted from global plan with resolution of value specified. If negative: disabled - max_global_plan_lookahead_dist: 3.0 # Specify max length of the subset of the global plan taken into account for optimization - force_reinit_new_goal_dist: 1.0 # Basically skips hot-starting - feasibility_check_no_poses: 4 # Picks which pose on the predicted plan to check for feasibility each sampling interval - publish_feedback: false # Publish planner feedback containing full trajectory and list of active obstacles (Use for debugging) - shrink_horizon_backup: true # Allows the planner the horizon temporarily for detected issues - allow_init_with_backwards_motion: false # Allows for backwards trajectories (Can implement if we add rear sensors to the scooter) - exact_arc_length: false # If true: uses exact arc length in vel, acc, and turning rate computations. Uses more CPU. Have to test to see if Alienware can handle it - shrink_horizon_min_duration: 10.0 # Specify minimum duration for the reduced horizon in case an indeasible trajectory is detected + # Trajectory Configuration Parameters + dt_ref: 0.3 # Desired temporal resolution + dt_hysteresis: 0.1 # Hysteresis for automatic resizing depending on the current temporal resolution Says recommended value is 10% of dt_ref but default is 0.1 + min_samples: 3 # Should always be greater than 2 + global_plan_overwrite_orientation: true # Overwrite orientation of local subgoals provided by global planner + global_plan_viapoint_sep: -0.1 # If positive: viapoints are extracted from global plan with resolution of value specified. If negative: disabled + max_global_plan_lookahead_dist: 3.0 # Specify max length of the subset of the global plan taken into account for optimization + force_reinit_new_goal_dist: 1.0 # Basically skips hot-starting + feasibility_check_no_poses: 4 # Picks which pose on the predicted plan to check for feasibility each sampling interval + publish_feedback: false # Publish planner feedback containing full trajectory and list of active obstacles (Use for debugging) + shrink_horizon_backup: true # Allows the planner the horizon temporarily for detected issues + allow_init_with_backwards_motion: false # Allows for backwards trajectories (Can implement if we add rear sensors to the scooter) + exact_arc_length: false # If true: uses exact arc length in vel, acc, and turning rate computations. Uses more CPU. Have to test to see if Alienware can handle it + shrink_horizon_min_duration: 10.0 # Specify minimum duration for the reduced horizon in case an indeasible trajectory is detected - - -# Obstacle Parameters - min_obstacle_dist: 3.0 # Change depending on what map we are using - include_costmap_obstacles: true # Uses all information from local_costmap (Don't make costmap resolution too high) - costmap_obstacles_behind_robot_dist: 1.0 # Limits the occupied local costmap behind robot - obstacle_poses_affected: 30 # Each obstacle position is attached to the closest pose on the trajectory in order to keep a distance - inflation_dist: 0.6 # Buffer zone around obstacles with non-zero penalty costs - include_dynamic_obstacles: false # Motion of obstacles with non-zero velocity is predicted - legacy_obstacle_inclusion: false # The strategy of connecting trajectory poses with obstacles for optimization. False: new method True: false method. Read documentation for more + # Obstacle Parameters + min_obstacle_dist: 3.0 # Change depending on what map we are using + include_costmap_obstacles: true # Uses all information from local_costmap (Don't make costmap resolution too high) + costmap_obstacles_behind_robot_dist: 1.0 # Limits the occupied local costmap behind robot + obstacle_poses_affected: 30 # Each obstacle position is attached to the closest pose on the trajectory in order to keep a distance + inflation_dist: 0.6 # Buffer zone around obstacles with non-zero penalty costs + include_dynamic_obstacles: false # Motion of obstacles with non-zero velocity is predicted + legacy_obstacle_inclusion: false # The strategy of connecting trajectory poses with obstacles for optimization. False: new method True: false method. Read documentation for more obstacle_association_force_inclusion_factor: 1.5 # No idea what this is -# Optimization Parameters -# penalty_epsilon: 0.1 # Adds small safety margin for penalty functions + # Optimization Parameters + # penalty_epsilon: 0.1 # Adds small safety margin for penalty functions weight_max_vel_x: 20.0 -# weight_max_vel_theta: 1.0 + # weight_max_vel_theta: 1.0 weight_acc_lim_x: 20.0 weight_acc_lim_theta: 20.0 -# weight_kinematics_nh: 1000 -# weight_kinematics_foward_drive: 1.0 -# weight_kinematics_turning_radius: 1.0 + # weight_kinematics_nh: 1000 + # weight_kinematics_foward_drive: 1.0 + # weight_kinematics_turning_radius: 1.0 weight_optimaltime: 20.0 -# weight_obstacle: 50.0 -# weight_viapoint: 1.0 -# weight_inflation: 0.1 -# weight_adapt_factor: 2.0 + # weight_obstacle: 50.0 + # weight_viapoint: 1.0 + # weight_inflation: 0.1 + # weight_adapt_factor: 2.0 + + # Extra Parameters + odom_topic: odom + map_frame: map -# Extra Parameters - odom_topic: "odom" - map_frame: "map" + footprint_model: # types: "point", "circular", "line", "two_circles", "polygon" + type: circular + radius: 5 # for type "circular" + # line_start: [-0.3, 0.0] # for type "line" + # line_end: [0.3, 0.0] # for type "line" + # front_offset: 0.2 # for type "two_circles" + # front_radius: 0.2 # for type "two_circles" + # rear_offset: 0.2 # for type "two_circles" + # rear_radius: 0.2 # for type "two_circles" + # vertices: [ [0.25, -0.05], [0.18, -0.05], [0.18, -0.18], [-0.19, -0.18], [-0.25, 0], [-0.19, 0.18], [0.18, 0.18], [0.18, 0.05], [0.25, 0.05] ] # for type "polygon" - footprint_model: # types: "point", "circular", "line", "two_circles", "polygon" - type: "circular" - radius: 5 # for type "circular" - # line_start: [-0.3, 0.0] # for type "line" - # line_end: [0.3, 0.0] # for type "line" - # front_offset: 0.2 # for type "two_circles" - # front_radius: 0.2 # for type "two_circles" - # rear_offset: 0.2 # for type "two_circles" - # rear_radius: 0.2 # for type "two_circles" - # vertices: [ [0.25, -0.05], [0.18, -0.05], [0.18, -0.18], [-0.19, -0.18], [-0.25, 0], [-0.19, 0.18], [0.18, 0.18], [0.18, 0.05], [0.25, 0.05] ] # for type "polygon" +# yamllint enable rule:line-length diff --git a/ros/docker/navigation/scooter_launch/param/teb_new.yaml b/ros/docker/navigation/scooter_launch/param/teb_new.yaml index 0722e1f9e..1a002bae3 100644 --- a/ros/docker/navigation/scooter_launch/param/teb_new.yaml +++ b/ros/docker/navigation/scooter_launch/param/teb_new.yaml @@ -1,83 +1,98 @@ +--- TebLocalPlannerROS: - odom_topic: odom - map_frame: /map + odom_topic: odom + map_frame: /map - # Trajectory + # Trajectory - teb_autosize: True - dt_ref: 0.3 - dt_hysteresis: 0.1 - global_plan_overwrite_orientation: false - max_global_plan_lookahead_dist: 9.0 - global_plan_viapoint_sep: 0.5 - feasibility_check_no_poses: 5 + teb_autosize: true + dt_ref: 0.3 + dt_hysteresis: 0.1 + global_plan_overwrite_orientation: false + max_global_plan_lookahead_dist: 9.0 + global_plan_viapoint_sep: 0.5 + feasibility_check_no_poses: 5 - # Robot + # Robot - max_vel_x: 4.0 - max_vel_x_backwards: 0.002 - max_vel_theta: 2.0 - acc_lim_x: 0.5 - acc_lim_theta: 1.0 - min_turning_radius: 3.0 - footprint_model: # types: "point", "circular", "two_circles", "line", "polygon" - type: "point" - radius: 2.5 # for type "circular" - line_start: [-0.3, 0.0] # for type "line" - line_end: [0.3, 0.0] # for type "line" - front_offset: 0.2 # for type "two_circles" - front_radius: 0.2 # for type "two_circles" - rear_offset: 0.2 # for type "two_circles" - rear_radius: 0.2 # for type "two_circles" - vertices: [ [0.25, -0.05], [0.18, -0.05], [0.18, -0.18], [-0.19, -0.18], [-0.25, 0], [-0.19, 0.18], [0.18, 0.18], [0.18, 0.05], [0.25, 0.05] ] # for type "polygon" + max_vel_x: 4.0 + max_vel_x_backwards: 0.002 + max_vel_theta: 2.0 + acc_lim_x: 0.5 + acc_lim_theta: 1.0 + min_turning_radius: 3.0 + footprint_model: + # types: "point", "circular", "two_circles", "line", "polygon" + type: point + radius: 2.5 # for type "circular" + line_start: # for type "line" + - -0.3 + - 0.0 + line_end: # for type "line" + - 0.3 + - 0.0 + front_offset: 0.2 # for type "two_circles" + front_radius: 0.2 # for type "two_circles" + rear_offset: 0.2 # for type "two_circles" + rear_radius: 0.2 # for type "two_circles" + vertices: # for type "polygon" - # GoalTolerance + # GoalTolerance - xy_goal_tolerance: 0.2 - yaw_goal_tolerance: 0.1 - free_goal_vel: False + - [0.25, -0.05] + - [0.18, -0.05] + - [0.18, -0.18] + - [-0.19, -0.18] + - [-0.25, 0] + - [-0.19, 0.18] + - [0.18, 0.18] + - [0.18, 0.05] + - [0.25, 0.05] + xy_goal_tolerance: 0.2 + yaw_goal_tolerance: 0.1 + free_goal_vel: false - # Obstacles + # Obstacles - min_obstacle_dist: 0.4 - include_costmap_obstacles: False - costmap_obstacles_behind_robot_dist: 1.0 - obstacle_poses_affected: 30 - costmap_converter_plugin: "" - costmap_converter_spin_thread: True - costmap_converter_rate: 5 + min_obstacle_dist: 0.4 + include_costmap_obstacles: false + costmap_obstacles_behind_robot_dist: 1.0 + obstacle_poses_affected: 30 + costmap_converter_plugin: '' + costmap_converter_spin_thread: true + costmap_converter_rate: 5 - # Optimization + # Optimization - no_inner_iterations: 5 - no_outer_iterations: 4 - optimization_activate: True - optimization_verbose: True - penalty_epsilon: 0.001 - weight_max_vel_x: 8 - weight_max_vel_theta: 3 - weight_acc_lim_x: 1 - weight_acc_lim_theta: 1 - weight_kinematics_nh: 100 - weight_kinematics_forward_drive: 100000 - weight_kinematics_turning_radius: 1 - weight_optimaltime: 20 - weight_obstacle: 1 - weight_dynamic_obstacle: 10 # not in use yet - alternative_time_cost: False # not in use yet - weight_viapoint: 0.5 + no_inner_iterations: 5 + no_outer_iterations: 4 + optimization_activate: true + optimization_verbose: true + penalty_epsilon: 0.001 + weight_max_vel_x: 8 + weight_max_vel_theta: 3 + weight_acc_lim_x: 1 + weight_acc_lim_theta: 1 + weight_kinematics_nh: 100 + weight_kinematics_forward_drive: 100000 + weight_kinematics_turning_radius: 1 + weight_optimaltime: 20 + weight_obstacle: 1 + weight_dynamic_obstacle: 10 # not in use yet + alternative_time_cost: false # not in use yet + weight_viapoint: 0.5 - # Homotopy Class Planner + # Homotopy Class Planner - enable_homotopy_class_planning: True - enable_multithreading: True - simple_exploration: False - max_number_classes: 4 - roadmap_graph_no_samples: 15 - roadmap_graph_area_width: 5 - h_signature_prescaler: 0.5 - h_signature_threshold: 0.1 - obstacle_keypoint_offset: 0.1 - obstacle_heading_threshold: 0.45 - visualize_hc_graph: False + enable_homotopy_class_planning: true + enable_multithreading: true + simple_exploration: false + max_number_classes: 4 + roadmap_graph_no_samples: 15 + roadmap_graph_area_width: 5 + h_signature_prescaler: 0.5 + h_signature_threshold: 0.1 + obstacle_keypoint_offset: 0.1 + obstacle_heading_threshold: 0.45 + visualize_hc_graph: false diff --git a/ros/docker/navigation/scooter_launch/param/teb_newnew.yaml b/ros/docker/navigation/scooter_launch/param/teb_newnew.yaml index 5062fa534..9d80c0e26 100644 --- a/ros/docker/navigation/scooter_launch/param/teb_newnew.yaml +++ b/ros/docker/navigation/scooter_launch/param/teb_newnew.yaml @@ -1,76 +1,79 @@ -#Visit http://wiki.ros.org/teb_local_planner for information regarding values +--- +# Visit http://wiki.ros.org/teb_local_planner for information regarding values TebLocalPlannerROS: - odom_topic: odom - map_frame: /map + odom_topic: odom + map_frame: /map - # Trajectory + # Trajectory - teb_autosize: True - dt_ref: 0.3 - dt_hysteresis: 0.1 - global_plan_overwrite_orientation: True - max_global_plan_lookahead_dist: 3.0 - feasibility_check_no_poses: 5 + teb_autosize: true + dt_ref: 0.3 + dt_hysteresis: 0.1 + global_plan_overwrite_orientation: true + max_global_plan_lookahead_dist: 3.0 + feasibility_check_no_poses: 5 - # Robot - cmd_angle_instead_rotvel: True - max_vel_x: 1.0 - max_vel_x_backwards: 0.01 - max_vel_theta: 0.3 - acc_lim_x: 1.5 - acc_lim_theta: 1.1 - min_turning_radius: 4.0 - wheelbase: 1.8 - footprint_model: # types: "point", "circular", "two_circles", "line", "polygon" - type: "circular" - radius: 0.2 + # Robot - # GoalTolerance + cmd_angle_instead_rotvel: true + max_vel_x: 1.0 + max_vel_x_backwards: 0.01 + max_vel_theta: 0.3 + acc_lim_x: 1.5 + acc_lim_theta: 1.1 + min_turning_radius: 4.0 + wheelbase: 1.8 + footprint_model: + # types: "point", "circular", "two_circles", "line", "polygon" + type: circular + radius: 0.2 - xy_goal_tolerance: 0.3 - yaw_goal_tolerance: 0.1 - free_goal_vel: False + # GoalTolerance - # Obstacles + xy_goal_tolerance: 0.3 + yaw_goal_tolerance: 0.1 + free_goal_vel: false - min_obstacle_dist: 0.16 - include_costmap_obstacles: True - costmap_obstacles_behind_robot_dist: 0.35 - obstacle_poses_affected: 30 - costmap_converter_plugin: "" - costmap_converter_spin_thread: True - costmap_converter_rate: 5 + # Obstacles - # Optimization + min_obstacle_dist: 0.16 + include_costmap_obstacles: true + costmap_obstacles_behind_robot_dist: 0.35 + obstacle_poses_affected: 30 + costmap_converter_plugin: '' + costmap_converter_spin_thread: true + costmap_converter_rate: 5 - no_inner_iterations: 5 - no_outer_iterations: 4 - optimization_activate: True - optimization_verbose: False - penalty_epsilon: 0.1 - weight_max_vel_x: 2 - weight_max_vel_theta: 1 - weight_acc_lim_x: 1 - weight_acc_lim_theta: 1 - weight_kinematics_nh: 1000 - weight_kinematics_forward_drive: 1000 - weight_kinematics_turning_radius: 1 - weight_optimaltime: 1 - weight_obstacle: 50 - weight_dynamic_obstacle: 10 # not in use yet - alternative_time_cost: False # not in use yet + # Optimization - # Homotopy Class Planner + no_inner_iterations: 5 + no_outer_iterations: 4 + optimization_activate: true + optimization_verbose: false + penalty_epsilon: 0.1 + weight_max_vel_x: 2 + weight_max_vel_theta: 1 + weight_acc_lim_x: 1 + weight_acc_lim_theta: 1 + weight_kinematics_nh: 1000 + weight_kinematics_forward_drive: 1000 + weight_kinematics_turning_radius: 1 + weight_optimaltime: 1 + weight_obstacle: 50 + weight_dynamic_obstacle: 10 # not in use yet + alternative_time_cost: false # not in use yet - enable_homotopy_class_planning: True - enable_multithreading: False - simple_exploration: False - max_number_classes: 4 - roadmap_graph_no_samples: 15 - roadmap_graph_area_width: 5 - h_signature_prescaler: 0.5 - h_signature_threshold: 0.1 - obstacle_keypoint_offset: 0.1 - obstacle_heading_threshold: 0.45 - visualize_hc_graph: False + # Homotopy Class Planner + + enable_homotopy_class_planning: true + enable_multithreading: false + simple_exploration: false + max_number_classes: 4 + roadmap_graph_no_samples: 15 + roadmap_graph_area_width: 5 + h_signature_prescaler: 0.5 + h_signature_threshold: 0.1 + obstacle_keypoint_offset: 0.1 + obstacle_heading_threshold: 0.45 + visualize_hc_graph: false diff --git a/ros/docker/rtabmap/rtabmap_launch/calibration.yaml b/ros/docker/rtabmap/rtabmap_launch/calibration.yaml index 985977cfa..f2aa6676e 100644 --- a/ros/docker/rtabmap/rtabmap_launch/calibration.yaml +++ b/ros/docker/rtabmap/rtabmap_launch/calibration.yaml @@ -5,14 +5,27 @@ image_width: 640 image_height: 360 camera_matrix: - rows: 3 - cols: 3 - data: [ 4.7689953613281250e+02, 0., 3.2061883544921875e+02, 0., - 4.7689953613281250e+02, 1.7850384521484375e+02, 0., 0., 1. ] + rows: 3 + cols: 3 + data: + - 4.7689953613281250e+02 + - 0. + - 3.2061883544921875e+02 + - 0. + - 4.7689953613281250e+02 + - 1.7850384521484375e+02 + - 0. + - 0. + - 1. distortion_coefficients: - rows: 1 - cols: 5 - data: [ 0., 0., 0., 0., 0. ] + rows: 1 + cols: 5 + data: + - 0. + - 0. + - 0. + - 0. + - 0. distortion_model: plumb_bob diff --git a/ros/docker/rtabmap/rtabmap_launch/params/mine-rtabmap.yaml b/ros/docker/rtabmap/rtabmap_launch/params/mine-rtabmap.yaml index f85ddc14b..3d0d57b9d 100644 --- a/ros/docker/rtabmap/rtabmap_launch/params/mine-rtabmap.yaml +++ b/ros/docker/rtabmap/rtabmap_launch/params/mine-rtabmap.yaml @@ -1,40 +1,43 @@ +--- # RTAB-map Configuration -database_path: "rtabmap.db" -frame_id: "base_link" -map_frame_id: "map" -wait_for_transform_duration: 0.2 -map_negative_poses_ignored: true -subscribe_depth: true -subscribe_stereo: false -subscribe_rgbd: false -publish_tf: true -approx_sync: true -gen_scan: true +database_path: rtabmap.db +frame_id: base_link +map_frame_id: map +wait_for_transform_duration: 0.2 +map_negative_poses_ignored: true +subscribe_depth: true +subscribe_stereo: false +subscribe_rgbd: false +publish_tf: true +approx_sync: true +gen_scan: true # fix covariance in odom topic -odom_frame_id: "odom" -odom_sensor_sync: true -odom_tf_linear_variance: 0.01 +odom_frame_id: odom +odom_sensor_sync: true +odom_tf_linear_variance: 0.01 odom_tf_angular_variance: 0.01 # feature type -Vis/FeatureType: "10" -Kp/DetectorStrategy: "10" -Rtabmap/DetectionRate: "1" +Vis/FeatureType: '10' +Kp/DetectorStrategy: '10' +Rtabmap/DetectionRate: '1' +# yamllint disable rule:line-length # RTAB-Map's parameters: do "rosrun rtabmap rtabmap --params" to see the list of available parameters -RGBD/ProximityBySpace: "true" # Local loop closure detection (using estimated position) with locations in WM -RGBD/OptimizeFromGraphEnd: "false" # Set to false to generate map correction between /map and /odom -RGBD/SavedLocalizationIgnored: "true" -Kp/MaxDepth: "6.0" -Reg/Strategy: "0" # Loop closure transformation: 0=Visual, 1=ICP, 2=Visual+ICP -Icp/CorrespondenceRatio: "0.3" -Vis/MinInliers: "15" # 3D visual words minimum inliers to accept loop closure -Vis/InlierDistance: "0.1" # 3D visual words correspondence distance -RGBD/AngularUpdate: "0.1" # Update map only if the robot is moving -RGBD/LinearUpdate: "0.1" # Update map only if the robot is moving -RGBD/ProximityPathMaxNeighbors: "0" -Rtabmap/TimeThr: "1" -Mem/RehearsalSimilarity: "0.30" -Reg/Force3DoF: "true" -GridGlobal/MinSize: "100" +RGBD/ProximityBySpace: 'true' # Local loop closure detection (using estimated position) with locations in WM +RGBD/OptimizeFromGraphEnd: 'false' # Set to false to generate map correction between /map and /odom +RGBD/SavedLocalizationIgnored: 'true' +Kp/MaxDepth: '6.0' +Reg/Strategy: '0' # Loop closure transformation: 0=Visual, 1=ICP, 2=Visual+ICP +Icp/CorrespondenceRatio: '0.3' +Vis/MinInliers: '15' # 3D visual words minimum inliers to accept loop closure +Vis/InlierDistance: '0.1' # 3D visual words correspondence distance +RGBD/AngularUpdate: '0.1' # Update map only if the robot is moving +RGBD/LinearUpdate: '0.1' # Update map only if the robot is moving +RGBD/ProximityPathMaxNeighbors: '0' +Rtabmap/TimeThr: '1' +Mem/RehearsalSimilarity: '0.30' +Reg/Force3DoF: 'true' +GridGlobal/MinSize: '100' +# yamllint enable rule:line-length diff --git a/ros/docker/rtabmap/rtabmap_launch/params/rtabmap.yaml b/ros/docker/rtabmap/rtabmap_launch/params/rtabmap.yaml index ae3b2a84d..c7839f059 100644 --- a/ros/docker/rtabmap/rtabmap_launch/params/rtabmap.yaml +++ b/ros/docker/rtabmap/rtabmap_launch/params/rtabmap.yaml @@ -1,30 +1,34 @@ +--- # RTAB-Map configuration -subscribe_depth: false -subscribe_rgbd: true -subscribe_rgb: false -subscribe_stereo: false -subscribe_scan: false -subscribe_scan_cloud: true # lidar on!! -subscribe_user_data: false -subscribe_odom_info: false +subscribe_depth: false +subscribe_rgbd: true +subscribe_rgb: false +subscribe_stereo: false +subscribe_scan: false +subscribe_scan_cloud: true # lidar on!! +subscribe_user_data: false +subscribe_odom_info: false # subscribe_odometry: false gen_scan: true -database_path: "~/.ros/rtabmap.db" -config_path: "~/.ros/rtabmap.cfg" +database_path: ~/.ros/rtabmap.db +config_path: ~/.ros/rtabmap.cfg -frame_id: "base_link" -map_frame_id: "map" -odom_frame_id: "world" # odometry from odom msg to have covariance - Remapped by launch file -# odom_tf_angular_variance: 0.03 # If TF is used to get odometry, this is the default angular variance -# odom_tf_linear_variance: 0.03 # If TF is used to get odometry, this is the default linear variance -tf_delay: 0.02 -publish_tf: true # Set to false if fusing different poses (map->odom) with UKF +frame_id: base_link +map_frame_id: map +# odometry from odom msg to have covariance - Remapped by launch file +odom_frame_id: world +# If TF is used to get odometry, this is the default angular variance +# odom_tf_angular_variance: 0.03 +# If TF is used to get odometry, this is the default linear variance +# odom_tf_linear_variance: 0.03 +tf_delay: 0.02 +publish_tf: true # Set to false if fusing different poses (map->odom) with UKF -odom_sensor_sync: false -wait_for_transform_duration: 10.0 +odom_sensor_sync: false +wait_for_transform_duration: 10.0 queue_size: 10 @@ -60,18 +64,20 @@ queue_size: 10 # RangeMin: 0.4 # RangeMax: 10 +# yamllint disable rule:line-length # GridGlobal: -# Eroded: false # Erode obstacle cells -# FootprintRadius: 0.18 # Footprint radius (m) used to clear all obstacles under the graph -# FullUpdate: true # When the graph is changed, the whole map will be reconstructed instead of moving individually each cells of the map. Also, data added to cache won't be released after updating the map. This process is longer but more robust to drift that would erase some parts of the map when it should not -# MaxNodes: 0 # Maximum nodes assembled in the map starting from the last node (0=unlimited) -# MinSize: 1.0 # Minimum map size (m) -# OccupancyThr: 0.55 # Occupancy threshold (value between 0 and 1) -# ProbClampingMax: 0.971 # Probability clamping maximum (value between 0 and 1) -# ProbClampingMin: 0.1192 # Probability clamping minimum (value between 0 and 1) -# ProbHit: 0.7 # Probability of a hit (value between 0.5 and 1) -# ProbMiss: 0.4 # Probability of a miss (value between 0 and 0.5) -# UpdateError: 0.01 # Graph changed detection error (m). Update map only if poses in new optimized graph have moved more than this value +# Eroded: false # Erode obstacle cells +# FootprintRadius: 0.18 # Footprint radius (m) used to clear all obstacles under the graph +# FullUpdate: true # When the graph is changed, the whole map will be reconstructed instead of moving individually each cells of the map. Also, data added to cache won't be released after updating the map. This process is longer but more robust to drift that would erase some parts of the map when it should not +# MaxNodes: 0 # Maximum nodes assembled in the map starting from the last node (0=unlimited) +# MinSize: 1.0 # Minimum map size (m) +# OccupancyThr: 0.55 # Occupancy threshold (value between 0 and 1) +# ProbClampingMax: 0.971 # Probability clamping maximum (value between 0 and 1) +# ProbClampingMin: 0.1192 # Probability clamping minimum (value between 0 and 1) +# ProbHit: 0.7 # Probability of a hit (value between 0.5 and 1) +# ProbMiss: 0.4 # Probability of a miss (value between 0 and 0.5) +# UpdateError: 0.01 # Graph changed detection error (m). Update map only if poses in new optimized graph have moved more than this value +# yamllint enable rule:line-length # Reg: # Force3DoF: false @@ -84,7 +90,7 @@ queue_size: 10 # ResetCountdown: 1 Icp: - Strategy: 2 + Strategy: 2 # RGBD: # OptimizeRobust: true