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(radar_tracks_msgs_converter): rework parameters #4911

Closed
1 change: 1 addition & 0 deletions perception/radar_tracks_msgs_converter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,4 +25,5 @@ endif()
ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
update_rate_hz: 20.0
new_frame_id: "base_link"
use_twist_compensation: false
kminoda marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,14 @@
<arg name="input/odometry" default="/localization/kinematic_state"/>
<arg name="output/radar_detected_objects" default="output/radar_detected_objects"/>
<arg name="output/radar_tracked_objects" default="output/radar_tracked_objects"/>
<arg name="update_rate_hz" default="20.0"/>
<arg name="use_twist_compensation" default="false"/>
<!-- Parameter -->
<arg name="config_file" default="$(find-pkg-share radar_tracks_msgs_converter)/config/radar_tracks_msgs_converter.param.yaml"/>

<node pkg="radar_tracks_msgs_converter" exec="radar_tracks_msgs_converter_node" name="radar_tracks_msgs_converter" output="screen">
<remap from="~/input/radar_objects" to="$(var input/radar_objects)"/>
<remap from="~/input/odometry" to="$(var input/odometry)"/>
<remap from="~/output/radar_detected_objects" to="$(var output/radar_detected_objects)"/>
<remap from="~/output/radar_tracked_objects" to="$(var output/radar_tracked_objects)"/>
<param name="update_rate_hz" value="$(var update_rate_hz)"/>
<param name="use_twist_compensation" value="$(var use_twist_compensation)"/>
<param from="$(var config_file)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Radar Tracks Msgs Converter node",
"type": "object",
"definitions": {
"radar_tracks_msgs_converter": {
"type": "object",
"properties": {
"update_rate_hz": {
"type": "number",
"description": "The update rate [hz].",
"default": "20.0",
"minimum": 0.0
},
"new_frame_id": {
"type": "string",
"description": "The header frame of output topic.",
"default": "base_link"
kaspermeck-arm marked this conversation as resolved.
Show resolved Hide resolved
},
"use_twist_compensation": {
"type": "boolean",
"description": "If the parameter is true, then the twist of output objects' topic is compensated by ego vehicle motion.",
"default": "false"
}
},
"required": ["update_rate_hz", "new_frame_id", "use_twist_compensation"]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/radar_tracks_msgs_converter"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,9 @@
std::bind(&RadarTracksMsgsConverterNode::onSetParam, this, _1));

// Node Parameter
node_param_.update_rate_hz = declare_parameter<double>("update_rate_hz", 20.0);
node_param_.new_frame_id = declare_parameter<std::string>("new_frame_id", "base_link");
node_param_.use_twist_compensation = declare_parameter<bool>("use_twist_compensation", false);
node_param_.update_rate_hz = declare_parameter<double>("update_rate_hz");
node_param_.new_frame_id = declare_parameter<std::string>("new_frame_id");
node_param_.use_twist_compensation = declare_parameter<bool>("use_twist_compensation");

Check warning on line 83 in perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp#L81-L83

Added lines #L81 - L83 were not covered by tests

// Subscriber
sub_radar_ = create_subscription<RadarTracks>(
Expand Down
Loading