Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] authored and brkay54 committed Dec 28, 2023
1 parent a30bc17 commit e53b2a1
Showing 1 changed file with 12 additions and 12 deletions.
24 changes: 12 additions & 12 deletions tools/reaction_analyzer/include/reaction_analyzer_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,15 @@ using autoware_auto_planning_msgs::msg::Trajectory;
using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using ControlBuffer = std::pair<std::vector<AckermannControlCommand>, std::optional<AckermannControlCommand>>;
using ControlBuffer =
std::pair<std::vector<AckermannControlCommand>, std::optional<AckermannControlCommand>>;

using BufferVariant = std::variant<
ControlBuffer
// , std::vector<OtherMessageType> // Add other message types here
>;
using BufferVariant =
std::variant<ControlBuffer
// , std::vector<OtherMessageType> // Add other message types here
>;

enum class MessageType
{
enum class MessageType {
Unknown = 0,
AckermannControlCommand = 1,
};
Expand Down Expand Up @@ -118,7 +118,8 @@ class ReactionAnalyzerNode : public rclcpp::Node
private:
void initObservers(const ChainModules & modules);
std::vector<rclcpp::SubscriptionBase::SharedPtr> subscribers_;
void controlCommandOutputCallback(const std::string & node_name, const AckermannControlCommand::ConstSharedPtr msg_ptr);
void controlCommandOutputCallback(
const std::string & node_name, const AckermannControlCommand::ConstSharedPtr msg_ptr);

std::unordered_map<std::string, BufferVariant> messageBuffers_;

Expand Down Expand Up @@ -164,8 +165,7 @@ class ReactionAnalyzerNode : public rclcpp::Node
void onTimer();
void setControlCommandToBuffer(
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd);
std::optional<size_t> findFirstBrakeIdx(
const std::vector<AckermannControlCommand> & cmd_array);
std::optional<size_t> findFirstBrakeIdx(const std::vector<AckermannControlCommand> & cmd_array);

// Callbacks
void vehiclePoseCallback(const Odometry::ConstSharedPtr msg_ptr);
Expand All @@ -183,8 +183,8 @@ class ReactionAnalyzerNode : public rclcpp::Node
std::optional<rclcpp::Time> last_initialize_test_time_;

// measurement for control cmd
// std::optional<ControlCommandWithSeenTime> trajectory_follower_brake_cmd;
// std::optional<ControlCommandWithSeenTime> vehicle_cmd_gate_brake_cmd;
// std::optional<ControlCommandWithSeenTime> trajectory_follower_brake_cmd;
// std::optional<ControlCommandWithSeenTime> vehicle_cmd_gate_brake_cmd;

// Timer
rclcpp::TimerBase::SharedPtr timer_;
Expand Down

0 comments on commit e53b2a1

Please sign in to comment.