diff --git a/system/mrm_comfortable_stop_operator/schema/mrm_comfortablex_stop_operator.json b/system/mrm_comfortable_stop_operator/schema/mrm_comfortablex_stop_operator.json new file mode 100644 index 0000000000000..a8e7959fa479b --- /dev/null +++ b/system/mrm_comfortable_stop_operator/schema/mrm_comfortablex_stop_operator.json @@ -0,0 +1,45 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for mrm_comfortable_stop_operator", + "type": "object", + "definitions": { + "mrm_comfortable_stop_operator": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "default": 10, + "description": "Timer callback frequency [Hz]." + }, + "min_acceleration": { + "type": "number", + "default": -1.0, + "description": "Minimum acceleration for comfortable stop [m/s^2]." + }, + "max_jerk": { + "type": "number", + "default": 0.3, + "description": "Maximum jerk for comfortable stop [m/s^3]." + }, + "min_jerk": { + "type": "number", + "default": -0.3, + "description": "Minimum jerk for comfortable stop [m/s^3]." + } + }, + "required": ["update_rate", "min_acceleration", "max_jerk", "min_jerk"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/mrm_comfortable_stop_operator" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp index 5c9562463f891..dcc8290be4701 100644 --- a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp +++ b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp @@ -21,10 +21,10 @@ MrmComfortableStopOperator::MrmComfortableStopOperator(const rclcpp::NodeOptions : Node("mrm_comfortable_stop_operator", node_options) { // Parameter - params_.update_rate = static_cast(declare_parameter("update_rate", 1)); - params_.min_acceleration = declare_parameter("min_acceleration", -1.0); - params_.max_jerk = declare_parameter("max_jerk", 0.3); - params_.min_jerk = declare_parameter("min_jerk", 0.3); + params_.update_rate = static_cast(declare_parameter("update_rate")); + params_.min_acceleration = declare_parameter("min_acceleration"); + params_.max_jerk = declare_parameter("max_jerk"); + params_.min_jerk = declare_parameter("min_jerk"); // Server service_operation_ = create_service(