Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(joy_controller): rework parameters #3992

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions control/joy_controller/config/joy_controller.param.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
/**:
ros__parameters:
joy_type: DS4
update_rate: 10.0
accel_ratio: 3.0
brake_ratio: 5.0
Expand Down
118 changes: 118 additions & 0 deletions control/joy_controller/schema/joy_controller.schema.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Joy Controller node",
"type": "object",
"definitions": {
"joy_controller": {
"type": "object",
"properties": {
"joy_type": {
"type": "string",
"description": "Joy controller type",
"default": "DS4",
"enum": ["P65", "DS4", "G29"]
},
"update_rate": {
"type": "number",
"description": "Update rate to publish control commands",
"default": "10.0",
"exclusiveMinimum": 0
},
"accel_ratio": {
"type": "number",
"description": "Ratio to calculate acceleration (commanded acceleration is ratio * operation)",
"default": "3.0"
},
"brake_ratio": {
"type": "number",
"description": "Ratio to calculate deceleration (commanded acceleration is -ratio * operation)",
"default": "5.0"
},
"steer_ratio": {
"type": "number",
"description": "Ratio to calculate deceleration (commanded steer is ratio * operation)",
"default": "0.5"
},
"steering_angle_velocity": {
"type": "number",
"description": "Steering angle velocity for operation",
"default": "0.1"
},
"accel_sensitivity": {
"type": "number",
"description": "Sensitivity to calculate acceleration for external API (commanded acceleration is pow(operation, 1 / sensitivity))",
"default": "1.0",
"maximum": 1.0,
"exclusiveMinimum": 0.0
},
"brake_sensitivity": {
"type": "number",
"description": "Sensitivity to calculate deceleration for external API (commanded acceleration is pow(operation, 1 / sensitivity))",
"default": "1.0",
"maximum": 1.0,
"exclusiveMinimum": 0.0
},
"control_command": {
"type": "object",
"properties": {
"velocity_gain": {
"type": "number",
"description": "Ratio to calculate velocity by acceleration",
"default": "3.0"
},
"max_forward_velocity": {
"type": "number",
"description": "Absolute max velocity to go forward",
"default": "20.0",
"minimum": 0
},
"max_backward_velocity": {
"type": "number",
"description": "Absolute max velocity to go backward",
"default": "3.0",
"minimum": 0
},
"backward_accel_ratio": {
"type": "number",
"description": "Ratio to calculate deceleration (commanded acceleration is -ratio * operation)",
"default": "1.0"
}
},
"required": [
"velocity_gain",
"max_forward_velocity",
"max_backward_velocity",
"backward_accel_ratio"
],
"additionalProperties": false
}
},
"required": [
"joy_type",
"update_rate",
"accel_ratio",
"brake_ratio",
"steer_ratio",
"steering_angle_velocity",
"accel_sensitivity",
"brake_sensitivity",
"control_command"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/joy_controller"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Loading