diff --git a/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json b/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json new file mode 100644 index 0000000000000..5d4638d090807 --- /dev/null +++ b/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json @@ -0,0 +1,44 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for vehicle_velocity_converter", + "type": "object", + "definitions": { + "vehicle_velocity_converter": { + "type": "object", + "properties": { + "stddev_vx": { + "type": "number", + "default": 0.2, + "description": "speed scale factor (ideal value is 1.0)" + }, + "frame_id": { + "type": "string", + "description": "frame id for output message." + }, + "stddev_wz": { + "type": "number", + "default": 0.1, + "description": "standard deviation for vx." + }, + "speed_scale_factor": { + "type": "number", + "default": 1.0, + "description": "standard deviation for yaw rate." + } + }, + "required": ["stddev_vx", "frame_id", "stddev_wz", "speed_scale_factor"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/vehicle_velocity_converter" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp b/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp index 997e06e8c01b0..d88005459666d 100644 --- a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp +++ b/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp @@ -17,10 +17,10 @@ VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_converter") { // set covariance value for twist with covariance msg - stddev_vx_ = declare_parameter("velocity_stddev_xx", 0.2); - stddev_wz_ = declare_parameter("angular_velocity_stddev_zz", 0.1); - frame_id_ = declare_parameter("frame_id", "base_link"); - speed_scale_factor_ = declare_parameter("speed_scale_factor", 1.0); + stddev_vx_ = declare_parameter("velocity_stddev_xx"); + stddev_wz_ = declare_parameter("angular_velocity_stddev_zz"); + frame_id_ = declare_parameter("frame_id"); + speed_scale_factor_ = declare_parameter("speed_scale_factor"); vehicle_report_sub_ = create_subscription( "velocity_status", rclcpp::QoS{100},