-
Notifications
You must be signed in to change notification settings - Fork 1
Emergency braking #16
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
base: main-old-sim
Are you sure you want to change the base?
Changes from 7 commits
fd8d877
c5e8d9d
cea2870
28f7607
e2329d6
1894347
47ff0da
8755226
2edcfd1
13b0a63
2dbc93c
a3782ae
32d5540
e76021c
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,55 @@ | ||
| cmake_minimum_required(VERSION 3.8) | ||
| project(emergency_braking) | ||
|
|
||
| if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
| add_compile_options(-Wall -Wextra -Wpedantic) | ||
| endif() | ||
|
|
||
| # find dependencies | ||
| find_package(ament_cmake REQUIRED) | ||
| # uncomment the following section in order to fill in | ||
| # further dependencies manually. | ||
| # find_package(<dependency> REQUIRED) | ||
| find_package(rclcpp REQUIRED) | ||
| find_package(std_msgs REQUIRED) | ||
| find_package(nav_msgs REQUIRED) | ||
| find_package(visualization_msgs REQUIRED) | ||
| find_package(sensor_msgs REQUIRED) | ||
| find_package(ackermann_msgs REQUIRED) | ||
|
|
||
| find_package(tf2_ros REQUIRED) | ||
| find_package(tf2_geometry_msgs REQUIRED) | ||
|
|
||
| if(BUILD_TESTING) | ||
| find_package(ament_lint_auto REQUIRED) | ||
| # the following line skips the linter which checks for copyrights | ||
| # comment the line when a copyright and license is added to all source files | ||
| set(ament_cmake_copyright_FOUND TRUE) | ||
| # the following line skips cpplint (only works in a git repo) | ||
| # comment the line when this package is in a git repo and when | ||
| # a copyright and license is added to all source files | ||
| set(ament_cmake_cpplint_FOUND TRUE) | ||
| ament_lint_auto_find_test_dependencies() | ||
| endif() | ||
|
|
||
| add_executable(emergency_braking_node src/emergency_braking.cpp) | ||
| target_include_directories(emergency_braking_node PUBLIC include) | ||
|
|
||
|
|
||
|
|
||
| ament_target_dependencies(emergency_braking_node rclcpp std_msgs nav_msgs visualization_msgs sensor_msgs ackermann_msgs tf2_ros tf2_geometry_msgs) | ||
|
|
||
|
|
||
| # Install the meshes folder | ||
| #install(DIRECTORY assets/ | ||
| # DESTINATION share/${PROJECT_NAME}/assets | ||
| #) | ||
|
|
||
| install(TARGETS | ||
| emergency_braking_node | ||
|
|
||
| DESTINATION lib/${PROJECT_NAME} | ||
| ) | ||
|
|
||
|
|
||
| ament_package() | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,18 @@ | ||
| <?xml version="1.0"?> | ||
| <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | ||
| <package format="3"> | ||
| <name>emergency_braking</name> | ||
| <version>0.0.0</version> | ||
| <description>TODO: Package description</description> | ||
| <maintainer email="140906428+erinjhu@users.noreply.github.com">bolty</maintainer> | ||
| <license>TODO: License declaration</license> | ||
|
|
||
| <buildtool_depend>ament_cmake</buildtool_depend> | ||
|
|
||
| <test_depend>ament_lint_auto</test_depend> | ||
| <test_depend>ament_lint_common</test_depend> | ||
|
|
||
| <export> | ||
| <build_type>ament_cmake</build_type> | ||
| </export> | ||
| </package> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,65 @@ | ||
| #include <cmath> | ||
|
|
||
| #include "ackermann_msgs/msg/ackermann_drive_stamped.hpp" | ||
| #include "nav_msgs/msg/odometry.hpp" | ||
| #include "rclcpp/rclcpp.hpp" | ||
| #include "sensor_msgs/msg/laser_scan.hpp" | ||
|
|
||
| using std::placeholders::_1; | ||
|
|
||
| class EmergencyBraking : public rclcpp::Node { | ||
|
|
||
| public: | ||
| EmergencyBraking() : Node("emergency_braking_node") { | ||
| brake_pub_ = this->create_publisher<ackermann_msgs::msg::AckermannDriveStamped>("drive", 10); | ||
| scan_sub_ = this->create_subscription<sensor_msgs::msg::LaserScan>("scan", 10, std::bind(&EmergencyBraking::scan_callback, this, _1)); | ||
| odom_sub_ = this->create_subscription<nav_msgs::msg::Odometry>("ego_racecar/odom", 10, std::bind(&EmergencyBraking::odom_callback, this, _1)); | ||
|
||
| } | ||
|
|
||
| private: | ||
| double speed = 0.0; | ||
|
|
||
| rclcpp::Publisher<ackermann_msgs::msg::AckermannDriveStamped>::SharedPtr brake_pub_; | ||
| rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr scan_sub_; | ||
| rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_; | ||
|
|
||
| void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr msg) { | ||
| this->speed = msg->twist.twist.linear.x; | ||
| } | ||
|
|
||
| void scan_callback(const sensor_msgs::msg::LaserScan::ConstSharedPtr scan_msg) { | ||
| // calculate TTC | ||
| bool brake = false; | ||
| double threshold = 1; | ||
|
||
| for (std::size_t i = 0; i < scan_msg->ranges.size(); i++) { | ||
| double range = scan_msg->ranges[i]; | ||
| bool not_valid = std::isnan(range) || range > scan_msg->range_max || range < scan_msg->range_min; | ||
| if (not_valid) { | ||
| continue; | ||
| } | ||
| double component = this->speed * std::cos(scan_msg->angle_min + (double)i * scan_msg->angle_increment); | ||
| // ensure speed is not 0 (don't divide by 0) | ||
| double v = std::max(component, 0.001); | ||
| double ttc = range / v; | ||
| RCLCPP_INFO(this->get_logger(), "ttc: %f", ttc); | ||
| if (ttc < threshold) { | ||
| brake = true; | ||
| break; | ||
| } | ||
| } | ||
| // publish braking message by setting speed to 0 | ||
| if (brake) { | ||
| auto brake_msg = ackermann_msgs::msg::AckermannDriveStamped(); | ||
| brake_msg.drive.speed = 0.0; | ||
| RCLCPP_INFO(this->get_logger(), "stop car"); | ||
| this->brake_pub_->publish(brake_msg); | ||
| } | ||
| } | ||
| }; | ||
|
|
||
| int main(int argc, char** argv) { | ||
| rclcpp::init(argc, argv); | ||
| rclcpp::spin(std::make_shared<EmergencyBraking>()); | ||
| rclcpp::shutdown(); | ||
| return 0; | ||
| } | ||
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.