Skip to content

Commit a46f001

Browse files
style(pre-commit): autofix
1 parent 44aea04 commit a46f001

File tree

3 files changed

+38
-34
lines changed

3 files changed

+38
-34
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,44 +1,52 @@
11
# Overview
2+
23
This package is used to enable GNSS and NDT to be used together in localization.
3-
GNSS and NDT are different sources that generate poses for use in EKF. For EKF,
4-
the covariance values of the pose source are important. The GNSS system can provide
4+
GNSS and NDT are different sources that generate poses for use in EKF. For EKF,
5+
the covariance values of the pose source are important. The GNSS system can provide
56
us with its own error (RMSE) values. Using these error values, covariance values for
6-
GNSS can be calculated. However, in default autoware, NDT covariance values are determined
7-
by default values. While this package manages which pose source will be used by reference
8-
to the error values coming from GNSS, it also manages situations where GNSS and NDT are used together.
7+
GNSS can be calculated. However, in default autoware, NDT covariance values are determined
8+
by default values. While this package manages which pose source will be used by reference
9+
to the error values coming from GNSS, it also manages situations where GNSS and NDT are used together.
910

1011
## Flowchart
11-
Default Autoware Pose Source is only NDT:
1212

13-
![new_proposal-original.drawio.png](..%2F..%2F..%2F..%2F..%2F..%2F..%2FDocuments%2Fnew_proposal-original.drawio.png)
13+
Default Autoware Pose Source is only NDT:
14+
15+
![new_proposal-original.drawio.png](..%2F..%2F..%2F..%2F..%2F..%2F..%2FDocuments%2Fnew_proposal-original.drawio.png)
16+
17+
You can see how autoware_pose_covariance_modifier_node works in the diagram below:
1418

15-
You can see how autoware_pose_covariance_modifier_node works in the diagram below:
19+
![new_proposal-proposal.drawio.png](..%2F..%2F..%2F..%2F..%2F..%2F..%2FDocuments%2Fnew_proposal-proposal.drawio.png)
20+
21+
## Activate This Feuture
1622

17-
![new_proposal-proposal.drawio.png](..%2F..%2F..%2F..%2F..%2F..%2F..%2FDocuments%2Fnew_proposal-proposal.drawio.png)
18-
## Activate This Feuture
1923
This package is not used by default autoware, you need to activate it to use it.
2024

21-
To activate, you need to change the `use_autoware_pose_covariance_modifier` parameter to true within the [tier4_localization_launch](https://github.com/autowarefoundation/autoware.universe/blob/main/launch/tier4_localization_launch/launch/localization.launch.xml
22-
).
25+
To activate, you need to change the `use_autoware_pose_covariance_modifier` parameter to true within the [tier4_localization_launch](https://github.com/autowarefoundation/autoware.universe/blob/main/launch/tier4_localization_launch/launch/localization.launch.xml).
26+
2327
# Node
28+
2429
## Subscribed Topics
25-
| Name | Type | Description |
26-
|-------------------------------------| ------------------------------------------------ |------------------------|
27-
| `input_trusted_pose_with_cov_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input GNSS pose topic. |
28-
| `input_ndt_pose_with_cov_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input NDT pose topic. |
30+
31+
| Name | Type | Description |
32+
| ----------------------------------- | ----------------------------------------------- | ---------------------- |
33+
| `input_trusted_pose_with_cov_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input GNSS pose topic. |
34+
| `input_ndt_pose_with_cov_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input NDT pose topic. |
2935

3036
## Published Topics
31-
| Name | Type | Description |
32-
|-------------------------------------| ------------------------------------------------ |-----------------------------------------------------------------------|
33-
| `output_pose_with_covariance_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Output pose topic. It will be sent as input to ekf_localizer package. |
37+
38+
| Name | Type | Description |
39+
| ----------------------------------- | ----------------------------------------------- | --------------------------------------------------------------------- |
40+
| `output_pose_with_covariance_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Output pose topic. It will be sent as input to ekf_localizer package. |
3441

3542
## Parameters
36-
| Name | Type | Description |
37-
|-----------------------------|------------|--------------------------------------------------------------------------------|
38-
| `gnss_error_reliable_max` | `double` | Threshold value for the range in which GNSS error is most reliable. |
39-
| `gnss_error_unreliable_min` | `double` | Threshold value at which GNSS error is not considered reliable. |
40-
| `yaw_error_deg_threshold` | `double` | Threshold value to understand whether the yaw error is within reliable limits. |
4143

42-
### Important Notes:
43-
* In order to use this package, your GNSS sensor must provide you with the error value. If you do not have a GNSS sensor that provides you with the error value, you cannot use this package.
44+
| Name | Type | Description |
45+
| --------------------------- | -------- | ------------------------------------------------------------------------------ |
46+
| `gnss_error_reliable_max` | `double` | Threshold value for the range in which GNSS error is most reliable. |
47+
| `gnss_error_unreliable_min` | `double` | Threshold value at which GNSS error is not considered reliable. |
48+
| `yaw_error_deg_threshold` | `double` | Threshold value to understand whether the yaw error is within reliable limits. |
49+
50+
### Important Notes
4451

52+
- In order to use this package, your GNSS sensor must provide you with the error value. If you do not have a GNSS sensor that provides you with the error value, you cannot use this package.

localization/autoware_pose_covariance_modifier_node/src/autoware_pose_covariance_modifier_node.cpp

+3-7
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,9 @@
1919
AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode()
2020
: Node("AutowarePoseCovarianceModifierNode")
2121
{
22-
23-
gnss_error_reliable_max_ =
24-
this->declare_parameter<double>("gnss_error_reliable_max", 0.10);
25-
gnss_error_unreliable_min_ =
26-
this->declare_parameter<double>("gnss_error_unreliable_min", 0.25);
27-
yaw_error_deg_threshold_ =
28-
this->declare_parameter<double>("yaw_error_deg_threshold", 0.3);
22+
gnss_error_reliable_max_ = this->declare_parameter<double>("gnss_error_reliable_max", 0.10);
23+
gnss_error_unreliable_min_ = this->declare_parameter<double>("gnss_error_unreliable_min", 0.25);
24+
yaw_error_deg_threshold_ = this->declare_parameter<double>("yaw_error_deg_threshold", 0.3);
2925

3026
trusted_pose_with_cov_sub_ =
3127
this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(

localization/autoware_pose_covariance_modifier_node/src/include/autoware_pose_covariance_modifier_node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class AutowarePoseCovarianceModifierNode : public rclcpp::Node
5959
int pose_source_;
6060
rclcpp::Time trustedPoseCallbackTime;
6161

62-
double gnss_error_reliable_max_, gnss_error_unreliable_min_,yaw_error_deg_threshold_;
62+
double gnss_error_reliable_max_, gnss_error_unreliable_min_, yaw_error_deg_threshold_;
6363
};
6464

6565
#endif // AUTOWARE_POSE_COVARIANCE_MODIFIER_NODE_HPP_

0 commit comments

Comments
 (0)