Skip to content

Commit 57ab852

Browse files
add autoware pose covariance modifier node
Signed-off-by: meliketanrikulu <melike@leodrive.ai>
1 parent edc6ef0 commit 57ab852

File tree

10 files changed

+303
-1
lines changed

10 files changed

+303
-1
lines changed

launch/tier4_localization_launch/launch/localization.launch.xml

+1
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
<arg name="pose_source" description="A string consisting of ndt, yabloc, artag and eagleye joined by underscores no matter the order. e.g. ndt_yabloc"/>
44
<arg name="twist_source"/>
55
<arg name="system_run_mode"/>
6+
<arg name="use_autoware_pose_covariance_modifier" default="false"/>
67

78
<!-- parameter paths for ndt -->
89
<arg name="ndt_scan_matcher/pointcloud_preprocessor/crop_box_filter_measurement_range_param_path"/>

launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml

+4
Original file line numberDiff line numberDiff line change
@@ -113,4 +113,8 @@
113113
<arg name="input_pointcloud" value="$(var override_input_pointcloud)"/>
114114
</include>
115115
</group>
116+
117+
<group if="$(var use_autoware_pose_covariance_modifier)">
118+
<include file="$(find-pkg-share autoware_pose_covariance_modifier_node)/launch/autoware_pose_covariance_modifier_node.launch.xml" />
119+
</group>
116120
</launch>

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

+5-1
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,13 @@
11
<?xml version="1.0"?>
22
<launch>
3+
4+
<let name="ekf_input_pose_with_cov_name" if="$(eval &quot;'$(var use_autoware_pose_covariance_modifier)'=='true'&quot;)" value="/localization/autoware_pose_covariance_modifier/pose_with_covariance"/>
5+
<let name="ekf_input_pose_with_cov_name" if="$(eval &quot;'$(var use_autoware_pose_covariance_modifier)'=='false'&quot;)" value="/localization/pose_estimator/pose_with_covariance"/>
6+
37
<group>
48
<include file="$(find-pkg-share ekf_localizer)/launch/ekf_localizer.launch.xml">
59
<arg name="input_initial_pose_name" value="/initialpose3d"/>
6-
<arg name="input_pose_with_cov_name" value="/localization/pose_estimator/pose_with_covariance"/>
10+
<arg name="input_pose_with_cov_name" value="$(var ekf_input_pose_with_cov_name)"/>
711
<arg name="input_twist_with_cov_name" value="/localization/twist_estimator/twist_with_covariance"/>
812
<arg name="output_odom_name" value="kinematic_state"/>
913
<arg name="output_pose_name" value="pose"/>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
cmake_minimum_required(VERSION 3.14)
2+
project(autoware_pose_covariance_modifier_node)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
find_package(rclcpp REQUIRED)
7+
find_package(geometry_msgs REQUIRED)
8+
set(NODE_NAME ${PROJECT_NAME})
9+
set(EXEC_NAME ${PROJECT_NAME}_exe)
10+
11+
add_executable(${PROJECT_NAME} src/autoware_pose_covariance_modifier_node.cpp)
12+
13+
ament_target_dependencies(${PROJECT_NAME} rclcpp geometry_msgs rcl_interfaces)
14+
15+
install(TARGETS
16+
${PROJECT_NAME}
17+
DESTINATION lib/${PROJECT_NAME}
18+
)
19+
include_directories(src/include/)
20+
21+
ament_auto_package(INSTALL_TO_SHARE
22+
config
23+
launch)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
# autoware_pose_covariance_modifier
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
/**:
2+
ros__parameters:
3+
# Threshold value for the range in which GNSS error is most reliable
4+
PositionErrorThreshold_1: 0.1 #meters
5+
6+
# Threshold value at which GNSS error is not considered reliable
7+
PositionErrorThreshold_2: 0.25 #meters
8+
9+
# Threshold value for yaw error
10+
YawErrorThreshold: 0.3 #degrees
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<launch>
3+
<arg name="input_trusted_pose_with_cov_topic" default="/sensing/gnss/pose_with_covariance" description="Trusted pose input topic name. "/>
4+
<arg name="input_ndt_pose_with_cov_topic" default="/localization/pose_estimator/pose_with_covariance" description="NDT output pose input topic name. "/>
5+
<arg name="output_pose_with_covariance_topic" default="/localization/autoware_pose_covariance_modifier/pose_with_covariance" description="Estimated self position with covariance"/>
6+
<arg name="param_file" default="$(find-pkg-share autoware_pose_covariance_modifier_node)/config/autoware_pose_covariance_modifier.param.yaml"/>
7+
8+
<node pkg="autoware_pose_covariance_modifier_node" exec="autoware_pose_covariance_modifier_node" name="autoware_pose_covariance_modifier_node" output="screen">
9+
<remap from="input_trusted_pose_with_cov_topic" to="$(var input_trusted_pose_with_cov_topic)"/>
10+
<remap from="input_ndt_pose_with_cov_topic" to="$(var input_ndt_pose_with_cov_topic)"/>
11+
<remap from="output_pose_with_covariance_topic" to="$(var output_pose_with_covariance_topic)"/>
12+
<param from="$(var param_file)"/>
13+
</node>
14+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>autoware_pose_covariance_modifier_node</name>
5+
<version>1.0.0</version>
6+
<description>Converts an autoware_msgs message to autoware_auto_msgs version and publishes it.</description>
7+
8+
<maintainer email="melike@leodrive.ai">Melike Tanrikulu</maintainer>
9+
10+
<license>Apache License 2.0</license>
11+
12+
<buildtool_depend>ament_cmake_auto</buildtool_depend>
13+
<buildtool_depend>autoware_cmake</buildtool_depend>
14+
15+
<build_depend>rosidl_default_generators</build_depend>
16+
17+
<depend>geometry_msgs</depend>
18+
<depend>rclcpp</depend>
19+
<depend>rclcpp_components</depend>
20+
21+
<export>
22+
<build_type>ament_cmake</build_type>
23+
</export>
24+
</package>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,157 @@
1+
// Copyright 2024 The Autoware Foundation
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "include/autoware_pose_covariance_modifier_node.hpp"
16+
17+
#include <rclcpp/rclcpp.hpp>
18+
19+
AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode() : Node("AutowarePoseCovarianceModifierNode")
20+
{
21+
trusted_pose_with_cov_sub_ =
22+
this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
23+
"input_trusted_pose_with_cov_topic", 10000,
24+
std::bind(
25+
&AutowarePoseCovarianceModifierNode::trusted_pose_with_cov_callback, this,
26+
std::placeholders::_1));
27+
28+
ndt_pose_with_cov_sub_ =
29+
this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
30+
"input_ndt_pose_with_cov_topic", 10000,
31+
std::bind(
32+
&AutowarePoseCovarianceModifierNode::ndt_pose_with_cov_callback, this,
33+
std::placeholders::_1));
34+
new_pose_estimator_pub_ =
35+
this->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
36+
"output_pose_with_covariance_topic", 10);
37+
38+
pose_source_pub_ =
39+
this->create_publisher<std_msgs::msg::String>(
40+
"autoware_pose_covariance_modifier/selected_pose_type",10);
41+
42+
}
43+
bool AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()
44+
{
45+
auto timeDiff = this->now() - trustedPoseCallbackTime;
46+
if (timeDiff.seconds() > 1.0) {
47+
return true;
48+
}
49+
return false;
50+
}
51+
void AutowarePoseCovarianceModifierNode::publishPoseSource(){
52+
53+
std_msgs::msg::String selected_pose_type;
54+
switch (pose_source_) {
55+
case static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS):
56+
selected_pose_type.data = "GNSS";
57+
break;
58+
case static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS_NDT):
59+
selected_pose_type.data = "GNSS_NDT";
60+
break;
61+
case static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT):
62+
selected_pose_type.data = "NDT";
63+
break;
64+
default:
65+
selected_pose_type.data = "Unknown";
66+
break;
67+
}
68+
pose_source_pub_->publish(selected_pose_type);
69+
}
70+
std::array<double, 36> AutowarePoseCovarianceModifierNode::ndt_covariance_modifier(
71+
std::array<double, 36> & in_ndt_covariance)
72+
{
73+
std::array<double, 36> ndt_covariance = in_ndt_covariance;
74+
75+
double position_error_threshold_1_ = this->declare_parameter<double>("PositionErrorThreshold_1",0.10);
76+
double position_error_threshold_2_ = this->declare_parameter<double>("PositionErrorThreshold_2",0.25);
77+
double yaw_error_threshold_ = this->declare_parameter<double>("YawErrorThreshold",0.3);
78+
79+
if (AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()) {
80+
RCLCPP_WARN(this->get_logger(), "Trusted Pose Timeout");
81+
pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT);
82+
return ndt_covariance;
83+
}
84+
85+
if (trustedPose.pose_average_rmse_xy <= position_error_threshold_1_ &&
86+
trustedPose.yaw_rmse_in_degrees < yaw_error_threshold_) {
87+
pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS);
88+
} else if (trustedPose.pose_average_rmse_xy <= position_error_threshold_2_) {
89+
/*
90+
* ndt_min_rmse_meters = in_ndt_rmse
91+
* ndt_max_rmse_meters = in_ndt_rmse * 2
92+
* ndt_rmse = ndt_max_rmse_meters - (gnss_rmse * (ndt_max_rmse_meters - ndt_min_rmse_meters) / normalization_coeff)
93+
*/
94+
double normalization_coeff = 0.1;
95+
ndt_covariance[0] = std::pow(
96+
((std::sqrt(in_ndt_covariance[0]) * 2) - std::sqrt(trusted_source_pose_with_cov.pose.covariance[0])) *
97+
(std::sqrt(in_ndt_covariance[0])) / normalization_coeff,
98+
2);
99+
ndt_covariance[7] = std::pow(
100+
((std::sqrt(in_ndt_covariance[7]) * 2) - std::sqrt(trusted_source_pose_with_cov.pose.covariance[7])) *
101+
(std::sqrt(in_ndt_covariance[7])) / normalization_coeff,
102+
2);
103+
ndt_covariance[14] = std::pow(
104+
((std::sqrt(in_ndt_covariance[14]) * 2) -
105+
std::sqrt(trusted_source_pose_with_cov.pose.covariance[14])) *
106+
(std::sqrt(in_ndt_covariance[14])) / normalization_coeff,
107+
2);
108+
109+
ndt_covariance[0] = std::max(ndt_covariance[0], in_ndt_covariance[0]);
110+
ndt_covariance[7] = std::max(ndt_covariance[7], in_ndt_covariance[7]);
111+
ndt_covariance[14] = std::max(ndt_covariance[14], in_ndt_covariance[14]);
112+
113+
pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS_NDT);
114+
} else {
115+
RCLCPP_INFO(this->get_logger(), "NDT input covariance values will be used ");
116+
pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT);
117+
}
118+
119+
publishPoseSource();
120+
121+
return ndt_covariance;
122+
}
123+
void AutowarePoseCovarianceModifierNode::ndt_pose_with_cov_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg){
124+
125+
std::array<double, 36> ndt_covariance_in_ = msg->pose.covariance;
126+
std::array<double, 36> out_ndt_covariance_ = ndt_covariance_modifier(ndt_covariance_in_);
127+
128+
geometry_msgs::msg::PoseWithCovarianceStamped ndt_pose_with_covariance = *msg;
129+
ndt_pose_with_covariance.pose.covariance = out_ndt_covariance_;
130+
if(pose_source_ != 0){
131+
new_pose_estimator_pub_->publish(ndt_pose_with_covariance);
132+
}
133+
}
134+
void AutowarePoseCovarianceModifierNode::trusted_pose_with_cov_callback(
135+
const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg)
136+
{
137+
trustedPoseCallbackTime = this->now();
138+
trusted_source_pose_with_cov = *msg;
139+
140+
trustedPose.pose_average_rmse_xy = (std::sqrt(trusted_source_pose_with_cov.pose.covariance[0]) +
141+
std::sqrt(trusted_source_pose_with_cov.pose.covariance[7])) /
142+
2;
143+
144+
trustedPose.yaw_rmse_in_degrees =
145+
std::sqrt(trusted_source_pose_with_cov.pose.covariance[35]) * 180 / M_PI;
146+
147+
if(pose_source_ != 2) {
148+
new_pose_estimator_pub_->publish(trusted_source_pose_with_cov);
149+
}
150+
}
151+
int main(int argc, char * argv[])
152+
{
153+
rclcpp::init(argc, argv);
154+
rclcpp::spin(std::make_shared<AutowarePoseCovarianceModifierNode>());
155+
rclcpp::shutdown();
156+
return 0;
157+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
// Copyright 2024 The Autoware Foundation
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
#ifndef AUTOWARE_POSE_COVARIANCE_MODIFIER_NODE_HPP_
15+
#define AUTOWARE_POSE_COVARIANCE_MODIFIER_NODE_HPP_
16+
17+
#include <rclcpp/rclcpp.hpp>
18+
19+
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
20+
#include <std_msgs/msg/string.hpp>
21+
#include <string>
22+
23+
class AutowarePoseCovarianceModifierNode : public rclcpp::Node
24+
{
25+
public:
26+
AutowarePoseCovarianceModifierNode();
27+
28+
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
29+
trusted_pose_with_cov_sub_;
30+
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
31+
ndt_pose_with_cov_sub_;
32+
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
33+
new_pose_estimator_pub_;
34+
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr
35+
pose_source_pub_;
36+
37+
void trusted_pose_with_cov_callback(
38+
const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg);
39+
void ndt_pose_with_cov_callback(
40+
const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg);
41+
std::array<double, 36> ndt_covariance_modifier(std::array<double, 36> & in_ndt_covariance);
42+
geometry_msgs::msg::PoseWithCovarianceStamped trusted_source_pose_with_cov;
43+
44+
bool checkTrustedPoseTimeout();
45+
46+
private:
47+
48+
struct trusted_pose_
49+
{
50+
double pose_average_rmse_xy = 0.0;
51+
double yaw_rmse_in_degrees = 0.0;
52+
} trustedPose;
53+
54+
enum class PoseSource{
55+
GNSS = 0,
56+
GNSS_NDT = 1,
57+
NDT = 2,
58+
};
59+
void publishPoseSource();
60+
int pose_source_;
61+
rclcpp::Time trustedPoseCallbackTime;
62+
};
63+
64+
#endif // AUTOWARE_POSE_COVARIANCE_MODIFIER_NODE_HPP_

0 commit comments

Comments
 (0)