Skip to content

Commit

Permalink
get steer msg by take instead of callback
Browse files Browse the repository at this point in the history
Signed-off-by: N-Eiki <eiki.nagata.2@tier4.jp>
  • Loading branch information
N-Eiki committed Jun 5, 2024
1 parent 97173bc commit 2ac6e68
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 18 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
//
// Copyright 2020 Tier IV, Inc. All rights reserved.
// Copyright 2024 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 @@ -27,8 +27,8 @@

#include <Eigen/Dense>

#include "autoware_vehicle_msgs/msg/steering_report.hpp"
#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp"
#include "autoware_auto_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 All @@ -44,6 +44,7 @@
#include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp"
#include "tier4_vehicle_msgs/msg/actuation_status_stamped.hpp"
#include "tier4_vehicle_msgs/srv/update_accel_brake_map.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

#include <fstream>
Expand All @@ -56,8 +57,8 @@
namespace accel_brake_map_calibrator
{

using autoware_vehicle_msgs::msg::SteeringReport;
using autoware_vehicle_msgs::msg::VelocityReport;
using autoware_auto_vehicle_msgs::msg::SteeringReport;
using autoware_auto_vehicle_msgs::msg::VelocityReport;
using geometry_msgs::msg::TwistStamped;
using nav_msgs::msg::OccupancyGrid;
using raw_vehicle_cmd_converter::AccelMap;
Expand Down Expand Up @@ -108,9 +109,11 @@ 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<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"};

// Service
rclcpp::Service<UpdateAccelBrakeMap>::SharedPtr update_map_dir_server_;
Expand Down Expand Up @@ -249,7 +252,7 @@ class AccelBrakeMapCalibrator : public rclcpp::Node
void callbackActuationCommand(const ActuationCommandStamped::ConstSharedPtr msg);
void callbackActuationStatus(const ActuationStatusStamped::ConstSharedPtr msg);
void callbackVelocity(const VelocityReport::ConstSharedPtr msg);
void callbackSteer(const SteeringReport::ConstSharedPtr msg);
// void callbackSteer(const SteeringReport::ConstSharedPtr msg);
bool callbackUpdateMapService(
const std::shared_ptr<rmw_request_id_t> request_header,
UpdateAccelBrakeMap::Request::SharedPtr req, UpdateAccelBrakeMap::Response::SharedPtr res);
Expand Down Expand Up @@ -378,4 +381,4 @@ class AccelBrakeMapCalibrator : public rclcpp::Node

} // namespace accel_brake_map_calibrator

#endif // ACCEL_BRAKE_MAP_CALIBRATOR__ACCEL_BRAKE_MAP_CALIBRATOR_NODE_HPP_
#endif // ACCEL_BRAKE_MAP_CALIBRATOR__ACCEL_BRAKE_MAP_CALIBRATOR_NODE_HPP_
1 change: 1 addition & 0 deletions vehicle/accel_brake_map_calibrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<maintainer email="tomoya.kimura@tier4.jp">Tomoya Kimura</maintainer>
<maintainer email="taiki.tanaka@tier4.jp">Taiki Tanaka</maintainer>
<maintainer email="takeshi.miura@tier4.jp">Takeshi Miura</maintainer>
<maintainer email="eiki.nagata@tier4.jp">Eiki Nagata</maintainer>

<license>Apache License 2.0</license>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
//
// Copyright 2020 Tier IV, Inc. All rights reserved.
// Copyright 2024 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 @@ -211,8 +211,6 @@ AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & nod
velocity_sub_ = create_subscription<VelocityReport>(
"~/input/velocity", queue_size,
std::bind(&AccelBrakeMapCalibrator::callbackVelocity, this, _1));
steer_sub_ = create_subscription<SteeringReport>(
"~/input/steer", queue_size, std::bind(&AccelBrakeMapCalibrator::callbackSteer, this, _1));
if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) {
actuation_status_sub_ = create_subscription<ActuationStatusStamped>(
"~/input/actuation_status", queue_size,
Expand Down Expand Up @@ -298,6 +296,9 @@ void AccelBrakeMapCalibrator::timerCallback()

/* valid check */

// take steer_ptr_ data
steer_ptr_ = steer_sub_.takeData();

// data check
if (
!twist_ptr_ || !steer_ptr_ || !accel_pedal_ptr_ || !brake_pedal_ptr_ ||
Expand Down Expand Up @@ -496,12 +497,6 @@ void AccelBrakeMapCalibrator::callbackVelocity(const VelocityReport::ConstShared
pushDataToVec(twist_msg, twist_vec_max_size_, &twist_vec_);
}

void AccelBrakeMapCalibrator::callbackSteer(const SteeringReport::ConstSharedPtr msg)
{
debug_values_.data.at(CURRENT_STEER) = msg->steering_tire_angle;
steer_ptr_ = msg;
}

void AccelBrakeMapCalibrator::callbackActuation(
const std_msgs::msg::Header header, const double accel, const double brake)
{
Expand Down Expand Up @@ -1691,4 +1686,4 @@ void AccelBrakeMapCalibrator::addLogToCSV(
<< ", " << new_accel_mse << "," << rmse_rate << std::endl;
}

} // namespace accel_brake_map_calibrator
} // namespace accel_brake_map_calibrator

0 comments on commit 2ac6e68

Please sign in to comment.