Skip to content

Commit cf3d631

Browse files
yuki-takagi-66N-Eikipre-commit-ci[bot]
authored
feat(autoware_accel_brake_map_calibrator): conditional actuation data processing based on source (#1497)
feat(autoware_accel_brake_map_calibrator): conditional actuation data processing based on source (autowarefoundation#8593) * fix: Conditional Actuation Data Processing Based on Source * style(pre-commit): autofix * delete extra comentout, indent * add take validation * style(pre-commit): autofix --------- Signed-off-by: N-Eiki <eiki.nagata.2@tier4.jp> Co-authored-by: eiki <53928021+N-Eiki@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent bab8174 commit cf3d631

File tree

1 file changed

+8
-7
lines changed

1 file changed

+8
-7
lines changed

vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -266,15 +266,16 @@ bool AccelBrakeMapCalibrator::get_current_pitch_from_tf(double * pitch)
266266
bool AccelBrakeMapCalibrator::take_data()
267267
{
268268
// take data from subscribers
269-
// take actuation data
270-
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData();
271-
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData();
272-
if (actuation_status_ptr) {
269+
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) {
270+
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData();
271+
if (!actuation_status_ptr) return false;
273272
take_actuation_status(actuation_status_ptr);
274-
} else if (actuation_cmd_ptr) {
273+
}
274+
// take actuation data
275+
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::COMMAND) {
276+
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData();
277+
if (!actuation_cmd_ptr) return false;
275278
take_actuation_command(actuation_cmd_ptr);
276-
} else {
277-
return false;
278279
}
279280

280281
// take velocity data

0 commit comments

Comments
 (0)