Skip to content

Commit

Permalink
feat(ekf_localizer): ignore dead band of velocity sensor (autowarefou…
Browse files Browse the repository at this point in the history
…ndation#5042)

* feat(ekf_localizer): ignore dead band of velocity sensor

Signed-off-by: kminoda <[email protected]>

* update

Signed-off-by: kminoda <[email protected]>

* update readme

Signed-off-by: kminoda <[email protected]>

* style(pre-commit): autofix

* update stop_filter as well

Signed-off-by: kminoda <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: kminoda <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
kminoda and pre-commit-ci[bot] committed Sep 21, 2023
1 parent d3e6757 commit 6a81ed5
Show file tree
Hide file tree
Showing 8 changed files with 27 additions and 7 deletions.
6 changes: 6 additions & 0 deletions localization/ekf_localizer/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,12 @@ note: process noise for positions x & y are calculated automatically from nonlin
| twist_no_update_count_threshold_warn | size_t | The threshold at which a WARN state is triggered due to the Twist Topic update not happening continuously for a certain number of times. | 50 |
| twist_no_update_count_threshold_error | size_t | The threshold at which an ERROR state is triggered due to the Twist Topic update not happening continuously for a certain number of times. | 250 |

### Misc

| Name | Type | Description | Default value |
| :-------------------------------- | :----- | :------------------------------------------------------------------------------------------------- | :------------- |
| threshold_observable_velocity_mps | double | Minimum value for velocity that will be used for EKF. Mainly used for dead zone in velocity sensor | 0.0 (disabled) |

## How to tune EKF parameters

### 0. Preliminaries
Expand Down
3 changes: 3 additions & 0 deletions localization/ekf_localizer/config/ekf_localizer.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,3 +27,6 @@
pose_no_update_count_threshold_error: 250
twist_no_update_count_threshold_warn: 50
twist_no_update_count_threshold_error: 250

# for velocity measurement limitation (Set 0.0 if you want to ignore)
threshold_observable_velocity_mps: 0.0 # [m/s]
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,9 @@ class HyperParameters
twist_no_update_count_threshold_warn(
node->declare_parameter("twist_no_update_count_threshold_warn", 50)),
twist_no_update_count_threshold_error(
node->declare_parameter("twist_no_update_count_threshold_error", 250))
node->declare_parameter("twist_no_update_count_threshold_error", 250)),
threshold_observable_velocity_mps(
node->declare_parameter("threshold_observable_velocity_mps", 0.5))
{
}

Expand All @@ -71,6 +73,7 @@ class HyperParameters
const size_t pose_no_update_count_threshold_error;
const size_t twist_no_update_count_threshold_warn;
const size_t twist_no_update_count_threshold_error;
const double threshold_observable_velocity_mps;
};

#endif // EKF_LOCALIZER__HYPER_PARAMETERS_HPP_
5 changes: 5 additions & 0 deletions localization/ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -385,6 +385,11 @@ void EKFLocalizer::callbackPoseWithCovariance(
void EKFLocalizer::callbackTwistWithCovariance(
geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg)
{
// Ignore twist if velocity is too small.
// Note that this inequality must not include "equal".
if (msg->twist.twist.linear.x < params_.threshold_observable_velocity_mps) {
msg->twist.covariance[0 * 6 + 0] = 10000.0;
}
twist_queue_.push(msg);
}

Expand Down
1 change: 1 addition & 0 deletions localization/stop_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,5 @@ ament_target_dependencies(stop_filter)
ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
4 changes: 4 additions & 0 deletions localization/stop_filter/config/stop_filter.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
vx_threshold: 0.1 # [m/s]
wz_threshold: 0.02 # [rad/s]
6 changes: 2 additions & 4 deletions localization/stop_filter/launch/stop_filter.launch.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
<launch>
<arg name="vx_threshold" default="0.01" description="[m/s]"/>
<arg name="wz_threshold" default="0.01" description="[rad/s]"/>
<arg name="param_path" default="$(find-pkg-share stop_filter)/config/stop_filter.param.yaml"/>
<arg name="input_odom_name" default="ekf_odom"/>
<arg name="output_odom_name" default="stop_filter_odom"/>
<arg name="debug_stop_flag" default="debug/stop_flag"/>
Expand All @@ -10,7 +9,6 @@
<remap from="output/odom" to="$(var output_odom_name)"/>
<remap from="debug/stop_flag" to="$(var debug_stop_flag)"/>

<param name="vx_threshold" value="$(var vx_threshold)"/>
<param name="wz_threshold" value="$(var wz_threshold)"/>
<param from="$(var param_path)"/>
</node>
</launch>
4 changes: 2 additions & 2 deletions localization/stop_filter/src/stop_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ using std::placeholders::_1;
StopFilter::StopFilter(const std::string & node_name, const rclcpp::NodeOptions & node_options)
: rclcpp::Node(node_name, node_options)
{
vx_threshold_ = declare_parameter("vx_threshold", 0.01);
wz_threshold_ = declare_parameter("wz_threshold", 0.01);
vx_threshold_ = declare_parameter<double>("vx_threshold");
wz_threshold_ = declare_parameter<double>("wz_threshold");

sub_odom_ = create_subscription<nav_msgs::msg::Odometry>(
"input/odom", 1, std::bind(&StopFilter::callbackOdometry, this, _1));
Expand Down

0 comments on commit 6a81ed5

Please sign in to comment.