Skip to content

Commit

Permalink
Merge branch 'feat-apply-autoware-prefix-for-control-control-performa…
Browse files Browse the repository at this point in the history
…nce-analysis' of github.com:sasakisasaki/autoware.universe into feat-apply-autoware-prefix-for-control-control-performance-analysis

Signed-off-by: Junya Sasaki <[email protected]>
  • Loading branch information
sasakisasaki committed Jan 22, 2025
2 parents 99eed53 + 8617022 commit 3486a40
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_
#define AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_
#ifndef AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_
#define AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/control_performance_analysis/control_performance_analysis_utils.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp"
#include "autoware_control_performance_analysis/msg/error_stamped.hpp"
#include "autoware_control_performance_analysis/msg/float_stamped.hpp"
Expand All @@ -40,12 +40,12 @@
namespace autoware::control::control_performance_analysis
{
using autoware_control_msgs::msg::Control;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
using autoware_control_performance_analysis::msg::DrivingMonitorStamped;
using autoware_control_performance_analysis::msg::Error;
using autoware_control_performance_analysis::msg::ErrorStamped;
using autoware_control_performance_analysis::msg::FloatStamped;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseArray;
using geometry_msgs::msg::Twist;
Expand Down Expand Up @@ -131,4 +131,4 @@ class ControlPerformanceAnalysisCore
};
} // namespace autoware::control::control_performance_analysis

#endif // AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_
#endif // AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_
#define AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_
#ifndef AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_
#define AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_

#include "autoware/control_performance_analysis/control_performance_analysis_core.hpp"
#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp"
Expand All @@ -37,10 +37,10 @@
namespace autoware::control::control_performance_analysis
{
using autoware_control_msgs::msg::Control;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
using autoware_control_performance_analysis::msg::DrivingMonitorStamped;
using autoware_control_performance_analysis::msg::ErrorStamped;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
using geometry_msgs::msg::PoseStamped;
using nav_msgs::msg::Odometry;

Expand Down Expand Up @@ -94,4 +94,4 @@ class ControlPerformanceAnalysisNode : public rclcpp::Node
};
} // namespace autoware::control::control_performance_analysis

#endif // AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_
#endif // AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_
#define AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_
#ifndef AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_
#define AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_

#include <Eigen/Core>
#include <Eigen/Geometry>
Expand Down Expand Up @@ -86,4 +86,4 @@ double curvatureFromThreePoints(
} // namespace utils
} // namespace autoware::control::control_performance_analysis

#endif // AUTOWARE__CONTROL__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_
#endif // AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ using geometry_msgs::msg::Quaternion;
ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore()
{
prev_target_vars_ = std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>();
prev_driving_vars_ = std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>();
prev_driving_vars_ =
std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>();
odom_history_ptr_ = std::make_shared<std::vector<Odometry>>();
p_.odom_interval_ = 0;
p_.curvature_interval_length_ = 10.0;
Expand All @@ -47,7 +48,8 @@ ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore(Params & p) : p_{
{
// prepare control performance struct
prev_target_vars_ = std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>();
prev_driving_vars_ = std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>();
prev_driving_vars_ =
std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>();
odom_history_ptr_ = std::make_shared<std::vector<Odometry>>();
}

Expand Down Expand Up @@ -251,7 +253,8 @@ bool ControlPerformanceAnalysisCore::calculateErrorVars()
lpf(error.error_energy, prev_error.error_energy);
}

prev_target_vars_ = std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>(error_vars);
prev_target_vars_ =
std::make_unique<autoware_control_performance_analysis::msg::ErrorStamped>(error_vars);

return true;
}
Expand Down Expand Up @@ -336,7 +339,9 @@ bool ControlPerformanceAnalysisCore::calculateDrivingVars()
lpf(curr.desired_steering_angle.data, prev->desired_steering_angle.data);
}

prev_driving_vars_ = std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>(driving_status_vars);
prev_driving_vars_ =
std::make_unique<autoware_control_performance_analysis::msg::DrivingMonitorStamped>(
driving_status_vars);

last_odom_header.stamp = odom_history_ptr_->at(odom_size - 1).header.stamp;
last_steering_report.stamp = current_vec_steering_msg_ptr_->stamp;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -198,4 +198,5 @@ bool ControlPerformanceAnalysisNode::isValidTrajectory(const Trajectory & traj)
} // namespace autoware::control::control_performance_analysis

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::control::control_performance_analysis::ControlPerformanceAnalysisNode)
RCLCPP_COMPONENTS_REGISTER_NODE(
autoware::control::control_performance_analysis::ControlPerformanceAnalysisNode)

0 comments on commit 3486a40

Please sign in to comment.