Skip to content

Commit

Permalink
feat(tier4_autoware_utils): divide into two classies
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed May 15, 2022
1 parent 17ea748 commit bebacf5
Show file tree
Hide file tree
Showing 5 changed files with 154 additions and 78 deletions.
3 changes: 2 additions & 1 deletion common/tier4_autoware_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@ find_package(Boost REQUIRED)
ament_auto_add_library(tier4_autoware_utils SHARED
src/tier4_autoware_utils.cpp
src/planning/planning_marker_helper.cpp
src/vehicle/vehicle_state_checker.cpp
src/vehicle/vehicle_stop_checker.cpp
src/vehicle/vehicle_arrival_checker.cpp
)

if(BUILD_TESTING)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 Tier IV, Inc.
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,13 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_
#define TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_
#ifndef TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_ARRIVAL_CHECKER_HPP_
#define TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_ARRIVAL_CHECKER_HPP_

#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

Expand All @@ -29,24 +28,20 @@ namespace tier4_autoware_utils
{

using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_vehicle_msgs::msg::VelocityReport;

class VehicleStateChecker
class VehicleArrivalChecker
{
public:
explicit VehicleStateChecker(rclcpp::Node * node);
explicit VehicleArrivalChecker(rclcpp::Node * node);

bool checkStopped(const double stop_duration) const;
bool isVehicleStopped(const double stop_duration) const;

bool checkStoppedAtStopPoint(const double stop_duration) const;

bool checkStoppedWithoutLocalization(const double stop_duration) const;
bool isVehicleStoppedAtStopPoint(const double stop_duration) const;

rclcpp::Logger getLogger() { return logger_; }

private:
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
rclcpp::Subscription<VelocityReport>::SharedPtr sub_velocity_status_;
rclcpp::Subscription<Trajectory>::SharedPtr sub_trajectory_;

rclcpp::Clock::SharedPtr clock_;
Expand All @@ -56,15 +51,13 @@ class VehicleStateChecker
Trajectory::SharedPtr trajectory_ptr_;

std::deque<geometry_msgs::msg::TwistStamped> twist_buffer_;
std::deque<VelocityReport> velocity_status_buffer_;

static constexpr double velocity_buffer_time_sec = 10.0;
static constexpr double th_arrived_distance_m = 1.0;

void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg);
void onVelocityStatus(const VelocityReport::SharedPtr msg);
void onTrajectory(const Trajectory::SharedPtr msg);
};
} // namespace tier4_autoware_utils

#endif // TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_
#endif // TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_ARRIVAL_CHECKER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STOP_CHECKER_HPP_
#define TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STOP_CHECKER_HPP_

#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/twist_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <deque>
#include <memory>

namespace tier4_autoware_utils
{

class VehicleStopChecker
{
public:
explicit VehicleStopChecker(rclcpp::Node * node);

bool isVehicleStopped(const double stop_duration) const;

rclcpp::Logger getLogger() { return logger_; }

private:
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;

rclcpp::Clock::SharedPtr clock_;
rclcpp::Logger logger_;

std::deque<geometry_msgs::msg::TwistStamped> twist_buffer_;

static constexpr double velocity_buffer_time_sec = 10.0;

void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg);
};
} // namespace tier4_autoware_utils

#endif // TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STOP_CHECKER_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 Tier IV, Inc.
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,33 +12,29 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "tier4_autoware_utils/vehicle/vehicle_state_checker.hpp"
#include "tier4_autoware_utils/vehicle/vehicle_arrival_checker.hpp"

#include "tier4_autoware_utils/trajectory/trajectory.hpp"

#include <string>

namespace tier4_autoware_utils
{
VehicleStateChecker::VehicleStateChecker(rclcpp::Node * node)
VehicleArrivalChecker::VehicleArrivalChecker(rclcpp::Node * node)
: clock_(node->get_clock()), logger_(node->get_logger())
{
using std::placeholders::_1;

sub_odom_ = node->create_subscription<nav_msgs::msg::Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1),
std::bind(&VehicleStateChecker::onOdom, this, _1));
std::bind(&VehicleArrivalChecker::onOdom, this, _1));

sub_trajectory_ = node->create_subscription<Trajectory>(
"/planning/scenario_planning/trajectory", rclcpp::QoS(1),
std::bind(&VehicleStateChecker::onTrajectory, this, _1));

sub_velocity_status_ = node->create_subscription<VelocityReport>(
"/vehicle/status/velocity_status", rclcpp::QoS(1),
std::bind(&VehicleStateChecker::onVelocityStatus, this, _1));
std::bind(&VehicleArrivalChecker::onTrajectory, this, _1));
}

bool VehicleStateChecker::checkStopped(const double stop_duration = 0.0) const
bool VehicleArrivalChecker::isVehicleStopped(const double stop_duration = 0.0) const
{
if (twist_buffer_.empty()) {
return false;
Expand Down Expand Up @@ -67,13 +63,13 @@ bool VehicleStateChecker::checkStopped(const double stop_duration = 0.0) const
return true;
}

bool VehicleStateChecker::checkStoppedAtStopPoint(const double stop_duration = 0.0) const
bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_duration = 0.0) const
{
if (!odometry_ptr_ || !trajectory_ptr_) {
return false;
}

if (!checkStopped(stop_duration)) {
if (!isVehicleStopped(stop_duration)) {
return false;
}

Expand All @@ -88,36 +84,7 @@ bool VehicleStateChecker::checkStoppedAtStopPoint(const double stop_duration = 0
th_arrived_distance_m;
}

bool VehicleStateChecker::checkStoppedWithoutLocalization(const double stop_duration = 0.0) const
{
if (velocity_status_buffer_.empty()) {
return false;
}

// Get velocities within stop_duration
const auto now = clock_->now();
std::vector<double> vs;
for (const auto & velocity : velocity_status_buffer_) {
vs.push_back(velocity.longitudinal_velocity);

const auto time_diff = now - velocity.header.stamp;
if (time_diff.seconds() >= stop_duration) {
break;
}
}

// Check all velocities
constexpr double stop_velocity = 1e-3;
for (const auto & v : vs) {
if (v >= stop_velocity) {
return false;
}
}

return true;
}

void VehicleStateChecker::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg)
void VehicleArrivalChecker::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg)
{
odometry_ptr_ = msg;

Expand All @@ -142,24 +109,5 @@ void VehicleStateChecker::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg)
}
}

void VehicleStateChecker::onVelocityStatus(const VelocityReport::SharedPtr msg)
{
velocity_status_buffer_.push_front(*msg);

const auto now = clock_->now();
while (true) {
// Check oldest data time
const auto time_diff = now - velocity_status_buffer_.back().header.stamp;

// Finish when oldest data is newer than threshold
if (time_diff.seconds() <= velocity_buffer_time_sec) {
break;
}

// Remove old data
velocity_status_buffer_.pop_back();
}
}

void VehicleStateChecker::onTrajectory(const Trajectory::SharedPtr msg) { trajectory_ptr_ = msg; }
void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg) { trajectory_ptr_ = msg; }
} // namespace tier4_autoware_utils
82 changes: 82 additions & 0 deletions common/tier4_autoware_utils/src/vehicle/vehicle_stop_checker.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "tier4_autoware_utils/vehicle/vehicle_stop_checker.hpp"

#include <string>

namespace tier4_autoware_utils
{
VehicleStopChecker::VehicleStopChecker(rclcpp::Node * node)
: clock_(node->get_clock()), logger_(node->get_logger())
{
using std::placeholders::_1;

sub_odom_ = node->create_subscription<nav_msgs::msg::Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1),
std::bind(&VehicleStopChecker::onOdom, this, _1));
}

bool VehicleStopChecker::isVehicleStopped(const double stop_duration = 0.0) const
{
if (twist_buffer_.empty()) {
return false;
}

// Get velocities within stop_duration
const auto now = clock_->now();
std::vector<double> vs;
for (const auto & velocity : twist_buffer_) {
vs.push_back(velocity.twist.linear.x);

const auto time_diff = now - velocity.header.stamp;
if (time_diff.seconds() >= stop_duration) {
break;
}
}

// Check all velocities
constexpr double stop_velocity = 1e-3;
for (const auto & v : vs) {
if (v >= stop_velocity) {
return false;
}
}

return true;
}

void VehicleStopChecker::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg)
{
auto current_velocity = std::make_shared<geometry_msgs::msg::TwistStamped>();
current_velocity->header = msg->header;
current_velocity->twist = msg->twist.twist;

twist_buffer_.push_front(*current_velocity);

const auto now = clock_->now();
while (true) {
// Check oldest data time
const auto time_diff = now - twist_buffer_.back().header.stamp;

// Finish when oldest data is newer than threshold
if (time_diff.seconds() <= velocity_buffer_time_sec) {
break;
}

// Remove old data
twist_buffer_.pop_back();
}
}
} // namespace tier4_autoware_utils

0 comments on commit bebacf5

Please sign in to comment.