Skip to content

Commit 68143ae

Browse files
committed
build(control_performance_analysis): fix include paths and namespaces for messages
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 7507b2d commit 68143ae

7 files changed

+35
-35
lines changed

control/control_performance_analysis/README.md

+7-7
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77
This package is used as a tool to quantify the results of the control module.
88
That's why it doesn't interfere with the core logic of autonomous driving.
99

10-
Based on the various input from planning, control, and vehicle, it publishes the result of analysis as `control_performance_analysis::msg::ErrorStamped` defined in this package.
10+
Based on the various input from planning, control, and vehicle, it publishes the result of analysis as `autoware_control_performance_analysis::msg::ErrorStamped` defined in this package.
1111

1212
All results in `ErrorStamped` message are calculated in Frenet Frame of curve. Errors and velocity errors are calculated by using paper below.
1313

@@ -35,14 +35,14 @@ Error acceleration calculations are made based on the velocity calculations abov
3535

3636
### Output topics
3737

38-
| Name | Type | Description |
39-
| --------------------------------------- | -------------------------------------------------------- | --------------------------------------------------- |
40-
| `/control_performance/performance_vars` | control_performance_analysis::msg::ErrorStamped | The result of the performance analysis. |
41-
| `/control_performance/driving_status` | control_performance_analysis::msg::DrivingMonitorStamped | Driving status (acceleration, jerk etc.) monitoring |
38+
| Name | Type | Description |
39+
| --------------------------------------- | ----------------------------------------------------------------- | --------------------------------------------------- |
40+
| `/control_performance/performance_vars` | autoware_control_performance_analysis::msg::ErrorStamped | The result of the performance analysis. |
41+
| `/control_performance/driving_status` | autoware_control_performance_analysis::msg::DrivingMonitorStamped | Driving status (acceleration, jerk etc.) monitoring |
4242

4343
### Outputs
4444

45-
#### control_performance_analysis::msg::DrivingMonitorStamped
45+
#### autoware_control_performance_analysis::msg::DrivingMonitorStamped
4646

4747
| Name | Type | Description |
4848
| ---------------------------- | ----- | -------------------------------------------------------- |
@@ -53,7 +53,7 @@ Error acceleration calculations are made based on the velocity calculations abov
5353
| `desired_steering_angle` | float | [rad] |
5454
| `controller_processing_time` | float | Timestamp between last two control command messages [ms] |
5555

56-
#### control_performance_analysis::msg::ErrorStamped
56+
#### autoware_control_performance_analysis::msg::ErrorStamped
5757

5858
| Name | Type | Description |
5959
| ------------------------------------------ | ----- | ----------------------------------------------------------------------------------------------------------------- |

control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_core.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616
#define CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_
1717

1818
#include "control_performance_analysis/control_performance_analysis_utils.hpp"
19-
#include "control_performance_analysis/msg/driving_monitor_stamped.hpp"
20-
#include "control_performance_analysis/msg/error_stamped.hpp"
21-
#include "control_performance_analysis/msg/float_stamped.hpp"
19+
#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp"
20+
#include "autoware_control_performance_analysis/msg/error_stamped.hpp"
21+
#include "autoware_control_performance_analysis/msg/float_stamped.hpp"
2222
#include "motion_utils/trajectory/trajectory.hpp"
2323

2424
#include <Eigen/Core>
@@ -42,10 +42,10 @@ namespace control_performance_analysis
4242
using autoware_auto_control_msgs::msg::AckermannControlCommand;
4343
using autoware_auto_planning_msgs::msg::Trajectory;
4444
using autoware_auto_vehicle_msgs::msg::SteeringReport;
45-
using control_performance_analysis::msg::DrivingMonitorStamped;
46-
using control_performance_analysis::msg::Error;
47-
using control_performance_analysis::msg::ErrorStamped;
48-
using control_performance_analysis::msg::FloatStamped;
45+
using autoware_control_performance_analysis::msg::DrivingMonitorStamped;
46+
using autoware_control_performance_analysis::msg::Error;
47+
using autoware_control_performance_analysis::msg::ErrorStamped;
48+
using autoware_control_performance_analysis::msg::FloatStamped;
4949
using geometry_msgs::msg::Pose;
5050
using geometry_msgs::msg::PoseArray;
5151
using geometry_msgs::msg::Twist;

control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_node.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@
1616
#define CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_
1717

1818
#include "control_performance_analysis/control_performance_analysis_core.hpp"
19-
#include "control_performance_analysis/msg/driving_monitor_stamped.hpp"
20-
#include "control_performance_analysis/msg/error_stamped.hpp"
19+
#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp"
20+
#include "autoware_control_performance_analysis/msg/error_stamped.hpp"
2121

2222
#include <rclcpp/rclcpp.hpp>
2323
#include <signal_processing/lowpass_filter_1d.hpp>
@@ -39,8 +39,8 @@ namespace control_performance_analysis
3939
using autoware_auto_control_msgs::msg::AckermannControlCommand;
4040
using autoware_auto_planning_msgs::msg::Trajectory;
4141
using autoware_auto_vehicle_msgs::msg::SteeringReport;
42-
using control_performance_analysis::msg::DrivingMonitorStamped;
43-
using control_performance_analysis::msg::ErrorStamped;
42+
using autoware_control_performance_analysis::msg::DrivingMonitorStamped;
43+
using autoware_control_performance_analysis::msg::ErrorStamped;
4444
using geometry_msgs::msg::PoseStamped;
4545
using nav_msgs::msg::Odometry;
4646

Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
1-
control_performance_analysis/FloatStamped longitudinal_acceleration
2-
control_performance_analysis/FloatStamped longitudinal_jerk
3-
control_performance_analysis/FloatStamped lateral_acceleration
4-
control_performance_analysis/FloatStamped lateral_jerk
5-
control_performance_analysis/FloatStamped desired_steering_angle
6-
control_performance_analysis/FloatStamped controller_processing_time
1+
autoware_control_performance_analysis/FloatStamped longitudinal_acceleration
2+
autoware_control_performance_analysis/FloatStamped longitudinal_jerk
3+
autoware_control_performance_analysis/FloatStamped lateral_acceleration
4+
autoware_control_performance_analysis/FloatStamped lateral_jerk
5+
autoware_control_performance_analysis/FloatStamped desired_steering_angle
6+
autoware_control_performance_analysis/FloatStamped controller_processing_time
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,2 @@
11
std_msgs/Header header
2-
control_performance_analysis/Error error
2+
autoware_control_performance_analysis/Error error

control/control_performance_analysis/src/control_performance_analysis_core.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,8 @@ using geometry_msgs::msg::Quaternion;
3030

3131
ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore()
3232
{
33-
prev_target_vars_ = std::make_unique<msg::ErrorStamped>();
34-
prev_driving_vars_ = std::make_unique<msg::DrivingMonitorStamped>();
33+
prev_target_vars_ = std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>();
34+
prev_driving_vars_ = std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>();
3535
odom_history_ptr_ = std::make_shared<std::vector<Odometry>>();
3636
p_.odom_interval_ = 0;
3737
p_.curvature_interval_length_ = 10.0;
@@ -45,8 +45,8 @@ ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore()
4545
ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore(Params & p) : p_{p}
4646
{
4747
// prepare control performance struct
48-
prev_target_vars_ = std::make_unique<msg::ErrorStamped>();
49-
prev_driving_vars_ = std::make_unique<msg::DrivingMonitorStamped>();
48+
prev_target_vars_ = std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>();
49+
prev_driving_vars_ = std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>();
5050
odom_history_ptr_ = std::make_shared<std::vector<Odometry>>();
5151
}
5252

@@ -250,7 +250,7 @@ bool ControlPerformanceAnalysisCore::calculateErrorVars()
250250
lpf(error.error_energy, prev_error.error_energy);
251251
}
252252

253-
prev_target_vars_ = std::make_unique<msg::ErrorStamped>(error_vars);
253+
prev_target_vars_ = std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>(error_vars);
254254

255255
return true;
256256
}
@@ -336,7 +336,7 @@ bool ControlPerformanceAnalysisCore::calculateDrivingVars()
336336
}
337337

338338
prev_driving_vars_ =
339-
std::move(std::make_unique<msg::DrivingMonitorStamped>(driving_status_vars));
339+
std::move(std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>(driving_status_vars));
340340

341341
last_odom_header.stamp = odom_history_ptr_->at(odom_size - 1).header.stamp;
342342
last_steering_report.stamp = current_vec_steering_msg_ptr_->stamp;

control/control_performance_analysis/src/control_performance_analysis_node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,8 @@
1414

1515
#include "control_performance_analysis/control_performance_analysis_node.hpp"
1616

17-
#include "control_performance_analysis/msg/driving_monitor_stamped.hpp"
18-
#include "control_performance_analysis/msg/error_stamped.hpp"
17+
#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp"
18+
#include "autoware_control_performance_analysis/msg/error_stamped.hpp"
1919

2020
#include <vehicle_info_util/vehicle_info_util.hpp>
2121

@@ -25,8 +25,8 @@
2525
namespace
2626
{
2727
using autoware_auto_control_msgs::msg::AckermannControlCommand;
28-
using control_performance_analysis::msg::DrivingMonitorStamped;
29-
using control_performance_analysis::msg::ErrorStamped;
28+
using autoware_control_performance_analysis::msg::DrivingMonitorStamped;
29+
using autoware_control_performance_analysis::msg::ErrorStamped;
3030

3131
} // namespace
3232

0 commit comments

Comments
 (0)