Skip to content

Commit

Permalink
delete comment out \n add debug values of steer
Browse files Browse the repository at this point in the history
Signed-off-by: N-Eiki <[email protected]>
  • Loading branch information
N-Eiki committed Jun 5, 2024
1 parent cc08670 commit 4461684
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,7 @@ class AccelBrakeMapCalibrator : public rclcpp::Node
rclcpp::Publisher<CalibrationStatus>::SharedPtr calibration_status_pub_;

rclcpp::Subscription<VelocityReport>::SharedPtr velocity_sub_;
// rclcpp::Subscription<SteeringReport>::SharedPtr steer_sub_;
// rclcpp::Subscription<ActuationStatusStamped>::SharedPtr actuation_status_sub_;
// rclcpp::Subscription<ActuationCommandStamped>::SharedPtr actuation_cmd_sub_;

tier4_autoware_utils::InterProcessPollingSubscriber<SteeringReport> steer_sub_{
this, "~/input/steer"};
tier4_autoware_utils::InterProcessPollingSubscriber<ActuationStatusStamped> actuation_status_sub_{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -311,6 +311,8 @@ void AccelBrakeMapCalibrator::timerCallback()
return;
}

debug_values_.data.at(CURRENT_STEER) = steer_ptr_->steering_tire_angle;

// data check 2
if (
isTimeout(twist_ptr_->header.stamp, timeout_sec_) ||
Expand Down

0 comments on commit 4461684

Please sign in to comment.