-
Notifications
You must be signed in to change notification settings - Fork 682
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
feat(tier4_autoware_utils): add vehicle state checker #896
Merged
satoshi-ota
merged 9 commits into
autowarefoundation:main
from
satoshi-ota:feature/vehicle-state-checker
May 19, 2022
Merged
Changes from 8 commits
Commits
Show all changes
9 commits
Select commit
Hold shift + click to select a range
9a42092
feat(tier4_autoware_utils): add vehicle state checker
satoshi-ota 264a402
fix(tier4_autoware_utils): use absolute value
satoshi-ota 57e89e3
feat(tier4_autoware_utils): divide into two classies
satoshi-ota 904ada0
test(tier4_autoware_utils): add unit test for vehicle_state checker
satoshi-ota 642674b
fix(tier4_autoware_utils): impl class inheritance
satoshi-ota 2416f7e
docs(tier4_autoware_utils): add vehicle_state_checker document
satoshi-ota f09a0f8
fix(tier4_autoware_utils): into same loop
satoshi-ota 69e5364
fix(tier4_autoware_utils): fix variables name
satoshi-ota 9a85dcf
fix(tier4_autoware_utils): remove redundant codes
satoshi-ota File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,169 @@ | ||
# vehicle utils | ||
|
||
Vehicle utils provides a convenient library used to check vehicle status. | ||
|
||
## Feature | ||
|
||
The library contains following classes. | ||
|
||
### vehicle_stop_checker | ||
|
||
This class check whether the vehicle is stopped or not based on localization result. | ||
|
||
#### Subscribed Topics | ||
|
||
| Name | Type | Description | | ||
| ------------------------------- | ------------------------- | ---------------- | | ||
| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | vehicle odometry | | ||
|
||
#### Parameters | ||
|
||
| Name | Type | Default Value | Explanation | | ||
| -------------------------- | ------ | ------------- | --------------------------- | | ||
| `velocity_buffer_time_sec` | double | 10.0 | odometry buffering time [s] | | ||
|
||
#### Member functions | ||
|
||
```c++ | ||
bool isVehicleStopped(const double stop_duration) | ||
``` | ||
|
||
- Check simply whether the vehicle is stopped based on the localization result. | ||
- Returns `true` if the vehicle is stopped, even if system outputs a non-zero target velocity. | ||
|
||
#### Example Usage | ||
|
||
Necessary includes: | ||
|
||
```c++ | ||
#include <tier4_autoware_utils/vehicle/vehicle_state_checker.hpp> | ||
``` | ||
|
||
1.Create a checker instance. | ||
|
||
```c++ | ||
class SampleNode : public rclcpp::Node | ||
{ | ||
public: | ||
SampleNode() : Node("sample_node") | ||
{ | ||
vehicle_stop_checker_ = std::make_unique<VehicleStopChecker>(this); | ||
} | ||
|
||
std::unique_ptr<VehicleStopChecker> vehicle_stop_checker_; | ||
|
||
bool sampleFunc(); | ||
|
||
... | ||
} | ||
``` | ||
|
||
2.Check the vehicle state. | ||
|
||
```c++ | ||
|
||
bool SampleNode::sampleFunc() | ||
{ | ||
... | ||
|
||
const auto result_1 = vehicle_stop_checker_->isVehicleStopped(); | ||
|
||
... | ||
|
||
const auto result_2 = vehicle_stop_checker_->isVehicleStopped(3.0); | ||
|
||
... | ||
} | ||
|
||
``` | ||
|
||
### vehicle_arrival_checker | ||
|
||
This class check whether the vehicle arrive at stop point based on localization and planning result. | ||
|
||
#### Subscribed Topics | ||
|
||
| Name | Type | Description | | ||
| ---------------------------------------- | ---------------------------------------------- | ---------------- | | ||
| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | vehicle odometry | | ||
| `/planning/scenario_planning/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | trajectory | | ||
|
||
#### Parameters | ||
|
||
| Name | Type | Default Value | Explanation | | ||
| -------------------------- | ------ | ------------- | ---------------------------------------------------------------------- | | ||
| `velocity_buffer_time_sec` | double | 10.0 | odometry buffering time [s] | | ||
| `th_arrived_distance_m` | double | 1.0 | threshold distance to check if vehicle has arrived at target point [m] | | ||
|
||
#### Member functions | ||
|
||
```c++ | ||
bool isVehicleStopped(const double stop_duration) | ||
``` | ||
|
||
- Check simply whether the vehicle is stopped based on the localization result. | ||
- Returns `true` if the vehicle is stopped, even if system outputs a non-zero target velocity. | ||
|
||
```c++ | ||
bool isVehicleStoppedAtStopPoint(const double stop_duration) | ||
``` | ||
|
||
- Check whether the vehicle is stopped at stop point based on the localization and planning result. | ||
- Returns `true` if the vehicle is not only stopped but also arrived at stop point. | ||
|
||
#### Example Usage | ||
|
||
Necessary includes: | ||
|
||
```c++ | ||
#include <tier4_autoware_utils/vehicle/vehicle_state_checker.hpp> | ||
``` | ||
|
||
1.Create a checker instance. | ||
|
||
```c++ | ||
class SampleNode : public rclcpp::Node | ||
{ | ||
public: | ||
SampleNode() : Node("sample_node") | ||
{ | ||
vehicle_arrival_checker_ = std::make_unique<VehicleArrivalChecker>(this); | ||
} | ||
|
||
std::unique_ptr<VehicleArrivalChecker> vehicle_arrival_checker_; | ||
|
||
bool sampleFunc(); | ||
|
||
... | ||
} | ||
``` | ||
|
||
2.Check the vehicle state. | ||
|
||
```c++ | ||
|
||
bool SampleNode::sampleFunc1() | ||
{ | ||
... | ||
|
||
const auto result_1 = vehicle_arrival_checker_->isVehicleStopped(); | ||
|
||
... | ||
|
||
const auto result_2 = vehicle_arrival_checker_->isVehicleStopped(3.0); | ||
|
||
... | ||
|
||
const auto result_3 = vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(); | ||
|
||
... | ||
|
||
const auto result_4 = vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(3.0); | ||
|
||
... | ||
} | ||
``` | ||
|
||
## Assumptions / Known limits | ||
|
||
`vehicle_stop_checker` and `vehicle_arrival_checker` cannot check whether the vehicle is stopped more than `velocity_buffer_time_sec` second. |
76 changes: 76 additions & 0 deletions
76
common/tier4_autoware_utils/include/tier4_autoware_utils/vehicle/vehicle_state_checker.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,76 @@ | ||
// 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_STATE_CHECKER_HPP_ | ||
#define TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_ | ||
|
||
#include <rclcpp/rclcpp.hpp> | ||
|
||
#include <autoware_auto_planning_msgs/msg/trajectory.hpp> | ||
#include <geometry_msgs/msg/twist_stamped.hpp> | ||
#include <nav_msgs/msg/odometry.hpp> | ||
|
||
#include <deque> | ||
#include <memory> | ||
|
||
namespace tier4_autoware_utils | ||
{ | ||
|
||
using autoware_auto_planning_msgs::msg::Trajectory; | ||
using geometry_msgs::msg::TwistStamped; | ||
using nav_msgs::msg::Odometry; | ||
|
||
class VehicleStopChecker | ||
{ | ||
public: | ||
explicit VehicleStopChecker(rclcpp::Node * node); | ||
|
||
bool isVehicleStopped(const double stop_duration) const; | ||
|
||
rclcpp::Logger getLogger() { return logger_; } | ||
|
||
protected: | ||
rclcpp::Subscription<Odometry>::SharedPtr sub_odom_; | ||
rclcpp::Clock::SharedPtr clock_; | ||
rclcpp::Logger logger_; | ||
|
||
Odometry::SharedPtr odometry_ptr_; | ||
|
||
std::deque<TwistStamped> twist_buffer_; | ||
|
||
private: | ||
static constexpr double velocity_buffer_time_sec = 10.0; | ||
|
||
void onOdom(const Odometry::SharedPtr msg); | ||
}; | ||
|
||
class VehicleArrivalChecker : public VehicleStopChecker | ||
{ | ||
public: | ||
explicit VehicleArrivalChecker(rclcpp::Node * node); | ||
|
||
bool isVehicleStoppedAtStopPoint(const double stop_duration) const; | ||
|
||
private: | ||
static constexpr double th_arrived_distance_m = 1.0; | ||
|
||
rclcpp::Subscription<Trajectory>::SharedPtr sub_trajectory_; | ||
|
||
Trajectory::SharedPtr trajectory_ptr_; | ||
|
||
void onTrajectory(const Trajectory::SharedPtr msg); | ||
}; | ||
} // namespace tier4_autoware_utils | ||
|
||
#endif // TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
123 changes: 123 additions & 0 deletions
123
common/tier4_autoware_utils/src/vehicle/vehicle_state_checker.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,123 @@ | ||
// 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_state_checker.hpp" | ||
|
||
#include "tier4_autoware_utils/trajectory/trajectory.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<Odometry>( | ||
"/localization/kinematic_state", rclcpp::QoS(1), | ||
isamu-takagi marked this conversation as resolved.
Show resolved
Hide resolved
|
||
std::bind(&VehicleStopChecker::onOdom, this, _1)); | ||
} | ||
|
||
bool VehicleStopChecker::isVehicleStopped(const double stop_duration = 0.0) const | ||
{ | ||
if (twist_buffer_.empty()) { | ||
return false; | ||
} | ||
|
||
constexpr double stop_velocity = 1e-3; | ||
const auto now = clock_->now(); | ||
|
||
const auto time_buffer_back = now - twist_buffer_.back().header.stamp; | ||
if (time_buffer_back.seconds() < stop_duration) { | ||
return false; | ||
isamu-takagi marked this conversation as resolved.
Show resolved
Hide resolved
|
||
} | ||
|
||
const auto time_buffer_front = now - twist_buffer_.front().header.stamp; | ||
if (time_buffer_front.seconds() > stop_duration) { | ||
return twist_buffer_.front().twist.linear.x < stop_velocity; | ||
} | ||
|
||
// Get velocities within stop_duration | ||
for (const auto & velocity : twist_buffer_) { | ||
if (stop_velocity <= velocity.twist.linear.x) { | ||
return false; | ||
} | ||
|
||
const auto time_diff = now - velocity.header.stamp; | ||
if (time_diff.seconds() >= stop_duration) { | ||
break; | ||
} | ||
} | ||
|
||
return true; | ||
} | ||
|
||
void VehicleStopChecker::onOdom(const Odometry::SharedPtr msg) | ||
{ | ||
odometry_ptr_ = msg; | ||
|
||
auto current_velocity = std::make_shared<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(); | ||
} | ||
} | ||
|
||
VehicleArrivalChecker::VehicleArrivalChecker(rclcpp::Node * node) : VehicleStopChecker(node) | ||
{ | ||
using std::placeholders::_1; | ||
|
||
sub_trajectory_ = node->create_subscription<Trajectory>( | ||
"/planning/scenario_planning/trajectory", rclcpp::QoS(1), | ||
std::bind(&VehicleArrivalChecker::onTrajectory, this, _1)); | ||
} | ||
|
||
bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_duration = 0.0) const | ||
{ | ||
if (!odometry_ptr_ || !trajectory_ptr_) { | ||
return false; | ||
} | ||
|
||
if (!isVehicleStopped(stop_duration)) { | ||
return false; | ||
} | ||
|
||
const auto & p = odometry_ptr_->pose.pose.position; | ||
const auto idx = searchZeroVelocityIndex(trajectory_ptr_->points); | ||
|
||
if (!idx) { | ||
return false; | ||
} | ||
|
||
return std::abs(calcSignedArcLength(trajectory_ptr_->points, p, idx.get())) < | ||
th_arrived_distance_m; | ||
} | ||
|
||
void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg) { trajectory_ptr_ = msg; } | ||
} // namespace tier4_autoware_utils |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
In future, I want to set this parameter as global parameter.
FYI: #910