Skip to content

Commit

Permalink
feat(autoware_accel_brake_map_calibrator): conditional actuation data…
Browse files Browse the repository at this point in the history
… 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 <[email protected]>
Co-authored-by: eiki <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
3 people authored Aug 30, 2024
1 parent bab8174 commit cf3d631
Showing 1 changed file with 8 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -266,15 +266,16 @@ bool AccelBrakeMapCalibrator::get_current_pitch_from_tf(double * pitch)
bool AccelBrakeMapCalibrator::take_data()
{
// take data from subscribers
// take actuation data
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData();
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData();
if (actuation_status_ptr) {
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) {
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData();
if (!actuation_status_ptr) return false;
take_actuation_status(actuation_status_ptr);
} else if (actuation_cmd_ptr) {
}
// take actuation data
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::COMMAND) {
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData();
if (!actuation_cmd_ptr) return false;
take_actuation_command(actuation_cmd_ptr);
} else {
return false;
}

// take velocity data
Expand Down

0 comments on commit cf3d631

Please sign in to comment.