Skip to content

Commit

Permalink
undo copyright year.\n delete if nest for CodeScene Cloud Delta Analy…
Browse files Browse the repository at this point in the history
…sis.\n handle new msg

Signed-off-by: N-Eiki <eiki.nagata.2@tier4.jp>
  • Loading branch information
N-Eiki committed Jun 6, 2024
1 parent fedba85 commit 46d34ae
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 8 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
//
// Copyright 2024 Tier IV, Inc. All rights reserved.
// Copyright 2020 Tier IV, Inc. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -30,6 +30,7 @@

#include "autoware_vehicle_msgs/msg/steering_report.hpp"
#include "autoware_vehicle_msgs/msg/velocity_report.hpp"

#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "std_msgs/msg/bool.hpp"
Expand Down Expand Up @@ -59,6 +60,7 @@ namespace accel_brake_map_calibrator

using autoware_vehicle_msgs::msg::SteeringReport;
using autoware_vehicle_msgs::msg::VelocityReport;

using geometry_msgs::msg::TwistStamped;
using nav_msgs::msg::OccupancyGrid;
using raw_vehicle_cmd_converter::AccelMap;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
//
// Copyright 202 Tier IV, Inc. All rights reserved.
// Copyright 2020 Tier IV, Inc. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -261,6 +261,8 @@ bool AccelBrakeMapCalibrator::getCurrentPitchFromTF(double * pitch)
return true;
}



void AccelBrakeMapCalibrator::timerCallback()
{
update_count_++;
Expand All @@ -283,16 +285,17 @@ void AccelBrakeMapCalibrator::timerCallback()
// take data from subscribers

// take actuation data
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) {
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData();
if (!actuation_status_ptr) return;
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData();
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData();
if (actuation_status_ptr) {
takeActuationStatus(actuation_status_ptr);
}
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::COMMAND) {
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData();
if (!actuation_cmd_ptr) return;
else if (actuation_cmd_ptr) {
takeActuationCommand(actuation_cmd_ptr);
}
else {
return;
}

// take velocity data
VelocityReport::ConstSharedPtr velocity_ptr = velocity_sub_.takeData();
Expand Down

0 comments on commit 46d34ae

Please sign in to comment.