Skip to content

Commit a7ed3bb

Browse files
kminoda1222-takeshi
authored andcommitted
fix(vehicle_velocity_converter): simpify parameter inputs (#1727)
* fix(vehicle_velocity_converter): simpify parameter inputs Signed-off-by: kminoda <koji.m.minoda@gmail.com> * fix readme and default value Signed-off-by: kminoda <koji.m.minoda@gmail.com> * fix default value Signed-off-by: kminoda <koji.m.minoda@gmail.com> Signed-off-by: kminoda <koji.m.minoda@gmail.com>
1 parent 0b04db4 commit a7ed3bb

File tree

4 files changed

+17
-18
lines changed

4 files changed

+17
-18
lines changed

sensing/vehicle_velocity_converter/README.md

+5-4
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,8 @@ This package converts autoware_auto_vehicle_msgs::msg::VehicleReport message to
2020

2121
## Parameters
2222

23-
| Name | Type | Description |
24-
| ------------ | ------ | ----------------------------------------- |
25-
| `frame_id` | string | frame id for output message |
26-
| `covariance` | double | set covariance value to the twist message |
23+
| Name | Type | Description |
24+
| ---------------------------- | ------ | ------------------------------- |
25+
| `frame_id` | string | frame id for output message |
26+
| `velocity_stddev_xx` | double | standard deviation for vx |
27+
| `angular_velocity_stddev_zz` | double | standard deviation for yaw rate |
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,5 @@
11
/**:
22
ros__parameters:
3+
velocity_stddev_xx: 0.2 # [m/s]
4+
angular_velocity_stddev_zz: 0.1 # [rad/s]
35
frame_id: base_link
4-
twist_covariance:
5-
[
6-
0.04, 0.0, 0.0, 0.0, 0.0, 0.0,
7-
0.0, 10000.0, 0.0, 0.0, 0.0, 0.0,
8-
0.0, 0.0, 10000.0, 0.0, 0.0, 0.0,
9-
0.0, 0.0, 0.0, 10000.0, 0.0, 0.0,
10-
0.0, 0.0, 0.0, 0.0, 10000.0, 0.0,
11-
0.0, 0.0, 0.0, 0.0, 0.0, 0.01,
12-
]

sensing/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,8 @@ class VehicleVelocityConverter : public rclcpp::Node
4141
twist_with_covariance_pub_;
4242

4343
std::string frame_id_;
44+
double stddev_vx_;
45+
double stddev_wz_;
4446
std::array<double, 36> twist_covariance_;
4547
};
4648

sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp

+8-5
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,8 @@
1717
VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_converter")
1818
{
1919
// set covariance value for twist with covariance msg
20-
std::vector<double> covariance = declare_parameter<std::vector<double>>("twist_covariance");
21-
for (std::size_t i = 0; i < covariance.size(); ++i) {
22-
twist_covariance_[i] = covariance[i];
23-
}
20+
stddev_vx_ = declare_parameter("velocity_stddev_xx", 0.2);
21+
stddev_wz_ = declare_parameter("angular_velocity_stddev_zz", 0.1);
2422
frame_id_ = declare_parameter("frame_id", "base_link");
2523

2624
vehicle_report_sub_ = create_subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>(
@@ -44,7 +42,12 @@ void VehicleVelocityConverter::callbackVelocityReport(
4442
twist_with_covariance_msg.twist.twist.linear.x = msg->longitudinal_velocity;
4543
twist_with_covariance_msg.twist.twist.linear.y = msg->lateral_velocity;
4644
twist_with_covariance_msg.twist.twist.angular.z = msg->heading_rate;
47-
twist_with_covariance_msg.twist.covariance = twist_covariance_;
45+
twist_with_covariance_msg.twist.covariance[0 + 0 * 6] = stddev_vx_ * stddev_vx_;
46+
twist_with_covariance_msg.twist.covariance[1 + 1 * 6] = 10000.0;
47+
twist_with_covariance_msg.twist.covariance[2 + 2 * 6] = 10000.0;
48+
twist_with_covariance_msg.twist.covariance[3 + 3 * 6] = 10000.0;
49+
twist_with_covariance_msg.twist.covariance[4 + 4 * 6] = 10000.0;
50+
twist_with_covariance_msg.twist.covariance[5 + 5 * 6] = stddev_wz_ * stddev_wz_;
4851

4952
twist_with_covariance_pub_->publish(twist_with_covariance_msg);
5053
}

0 commit comments

Comments
 (0)