Skip to content

Commit ff867c7

Browse files
SakodaShintaropre-commit-ci[bot]
authored andcommitted
chore(twist2accel): rework parameters (autowarefoundation#6266)
* Added twist2accel.param.yaml Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> * Added twist2accel.schema.json Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> * Fixed README.md and description Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> * style(pre-commit): autofix * Removed default parameters Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> --------- Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 6e38a96 commit ff867c7

File tree

7 files changed

+48
-11
lines changed

7 files changed

+48
-11
lines changed

launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -27,10 +27,10 @@
2727

2828
<group>
2929
<include file="$(find-pkg-share twist2accel)/launch/twist2accel.launch.xml">
30-
<arg name="use_odom" value="true"/>
3130
<arg name="in_odom" value="/localization/kinematic_state"/>
3231
<arg name="in_twist" value="/localization/twist_estimator/twist_with_covariance"/>
3332
<arg name="out_accel" value="/localization/acceleration"/>
33+
<arg name="param_file" value="$(var twist2accel_param_path)"/>
3434
</include>
3535
</group>
3636

localization/twist2accel/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -13,4 +13,5 @@ ament_target_dependencies(twist2accel)
1313
ament_auto_package(
1414
INSTALL_TO_SHARE
1515
launch
16+
config
1617
)

localization/twist2accel/README.md

+1-4
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,7 @@ This package is responsible for estimating acceleration using the output of `ekf
2121

2222
## Parameters
2323

24-
| Name | Type | Description |
25-
| -------------------- | ------ | ------------------------------------------------------------------------- |
26-
| `use_odom` | bool | use odometry if true, else use twist input (default: true) |
27-
| `accel_lowpass_gain` | double | lowpass gain for lowpass filter in estimating acceleration (default: 0.9) |
24+
{{ json_to_markdown("localization/twist2accel/schema/twist2accel.schema.json") }}
2825

2926
## Future work
3027

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
use_odom: true
4+
accel_lowpass_gain: 0.9
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,13 @@
11
<launch>
2-
<arg name="use_odom" default="true"/>
3-
<arg name="accel_lowpass_gain" default="0.9"/>
2+
<arg name="param_file" default="$(find-pkg-share twist2accel)/config/twist2accel.param.yaml"/>
3+
44
<arg name="in_odom" default="in_odom"/>
55
<arg name="in_twist" default="in_twist"/>
66
<arg name="out_accel" default="out_accel"/>
77
<node pkg="twist2accel" exec="twist2accel" name="twist2accel" output="screen">
88
<remap from="input/odom" to="$(var in_odom)"/>
99
<remap from="input/twist" to="$(var in_twist)"/>
1010
<remap from="output/accel" to="$(var out_accel)"/>
11-
<param name="accel_lowpass_gain" value="$(var accel_lowpass_gain)"/>
12-
<param name="use_odom" value="$(var use_odom)"/>
11+
<param from="$(var param_file)"/>
1312
</node>
1413
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for twist2accel Nodes",
4+
"type": "object",
5+
"definitions": {
6+
"twist2accel": {
7+
"type": "object",
8+
"properties": {
9+
"use_odom": {
10+
"type": "boolean",
11+
"default": true,
12+
"description": "use odometry if true, else use twist input."
13+
},
14+
"accel_lowpass_gain": {
15+
"type": "number",
16+
"default": 0.9,
17+
"minimum": 0.0,
18+
"description": "lowpass gain for lowpass filter in estimating acceleration."
19+
}
20+
},
21+
"required": ["use_odom", "accel_lowpass_gain"]
22+
}
23+
},
24+
"properties": {
25+
"/**": {
26+
"type": "object",
27+
"properties": {
28+
"ros__parameters": {
29+
"$ref": "#/definitions/twist2accel"
30+
}
31+
},
32+
"required": ["ros__parameters"]
33+
}
34+
},
35+
"required": ["/**"]
36+
}

localization/twist2accel/src/twist2accel.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,8 @@ Twist2Accel::Twist2Accel(const std::string & node_name, const rclcpp::NodeOption
3535
pub_accel_ = create_publisher<geometry_msgs::msg::AccelWithCovarianceStamped>("output/accel", 1);
3636

3737
prev_twist_ptr_ = nullptr;
38-
accel_lowpass_gain_ = declare_parameter("accel_lowpass_gain", 0.5);
39-
use_odom_ = declare_parameter("use_odom", true);
38+
accel_lowpass_gain_ = declare_parameter<double>("accel_lowpass_gain");
39+
use_odom_ = declare_parameter<bool>("use_odom");
4040

4141
lpf_alx_ptr_ = std::make_shared<LowpassFilter1d>(accel_lowpass_gain_);
4242
lpf_aly_ptr_ = std::make_shared<LowpassFilter1d>(accel_lowpass_gain_);

0 commit comments

Comments
 (0)