From f1b160d1f7c067420cfc68c9408195c6f4d8e3b1 Mon Sep 17 00:00:00 2001 From: Tiago Garcia Date: Tue, 9 Jul 2024 15:28:56 +0100 Subject: [PATCH] Add V2XNode changes to documentation Signed-off-by: Tiago Garcia --- config/autoware_v2x.param.yaml | 4 ++-- docs/design/index.md | 12 +++++++++--- include/autoware_v2x/v2x_node.hpp | 2 -- launch/v2x.launch.xml | 4 ++-- src/cam_application.cpp | 4 +++- src/cpm_application.cpp | 26 +++++++++++++------------- src/v2x_node.cpp | 2 +- 7 files changed, 30 insertions(+), 24 deletions(-) diff --git a/config/autoware_v2x.param.yaml b/config/autoware_v2x.param.yaml index 80a1e0f..5b1bce5 100644 --- a/config/autoware_v2x.param.yaml +++ b/config/autoware_v2x.param.yaml @@ -1,4 +1,4 @@ /**: ros__parameters: - network_interface: "v2x_testing" - is_sender: true + network_interface: "wlp4s0" + is_sender: true \ No newline at end of file diff --git a/docs/design/index.md b/docs/design/index.md index b2d236a..ae0ee88 100644 --- a/docs/design/index.md +++ b/docs/design/index.md @@ -3,7 +3,7 @@ !!! Warning More to come -A V2X communication software stack called [Vanetza](https://github.com/riebl/vanetza) is integrated into the standalone autonomous driving software stack, [Autoware](https://github.com/autowarefoundation/autoware). The V2X stack and the autonomous driving stack can be decoupled, allowing other applications to utilize the V2X router as well. A high-level overview of the architecture is shown below. +A V2X communication software stack called [Vanetza](https://github.com/riebl/vanetza) is integrated into the standalone autonomous driving software stack, [Autoware](https://github.com/autowarefoundation/autoware). The V2X stack and the autonomous driving stack can be decoupled, allowing other applications to utilize the V2X router as well. A high-level overview of the architecture is shown below. ![AutowareV2X Architecture diagram](../figs/autowarev2x_architecture_v2.png) @@ -13,7 +13,7 @@ The V2XApp is responsible for managing the various facilities such as DENM, CAM, ## V2XNode -The V2XNode launches a ROS2 Node for AutowareV2X. Its main purpose is to act as the bridge interface between Autoware and AutowareV2X. Information that is to be utilized in V2X Applications are retreived from Autoware in the form of ROS2 topics. Similarily, information that is received by AutowareV2X through V2X communications is published as ROS2 topics in order to feed it back into Autoware. +The V2XNode launches a ROS2 Node for AutowareV2X. Its main purpose is to act as the bridge interface between Autoware and AutowareV2X. Information that is to be utilized in V2X Applications are retreived from Autoware in the form of ROS2 topics. Similarily, information that is received by AutowareV2X through V2X communications is published as ROS2 topics in order to feed it back into Autoware. ### Input @@ -21,6 +21,9 @@ The V2XNode launches a ROS2 Node for AutowareV2X. Its main purpose is to act as | -------------------- | ------------------------------- | ---------------- | | `/perception/object_recognition/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | Perceived Objects by Autoware | | `/tf` | `tf2_msgs::msg::TFMessage` | Pose of Ego Vehicle | +| `/vehicle/status/velocity_report` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | Velocity of Ego Vehicle | +| `/api/vehicle/status` | `autoware_adapi_v1_msgs::msg::VehicleStatus` | Vehicle Status (gear, steering angle, etc.) | +| `/api/vehicle/dimensions` | `autoware_adapi_v1_msgs::srv::GetVehicleDimensions` | Service to get Vehicle Dimensions | ### Output @@ -34,10 +37,13 @@ The V2XNode launches a ROS2 Node for AutowareV2X. Its main purpose is to act as | -------------------- | ---------------- | | `objectsCallback(const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg)` | Call `V2XApp::objectsCallback` | | `tfCallback` | Call `V2XApp::tfCallback` | +| `velocityReportCallback` | Call `V2XApp::velocityReportCallback` | +| `vehicleStatusCallback` | Call `V2XApp::vehicleStatusCallback` | +| `getVehicleDimensions` | Sends a request to the service used for vehicle dimensions | | `publishObjects(std::vector *objectsStack, int cpm_num)` | | | `publishCpmSenderObject` | Not used now | ## V2XApp -## CPM Facility \ No newline at end of file +## CPM Facility diff --git a/include/autoware_v2x/v2x_node.hpp b/include/autoware_v2x/v2x_node.hpp index 94ae5ed..a5941e2 100644 --- a/include/autoware_v2x/v2x_node.hpp +++ b/include/autoware_v2x/v2x_node.hpp @@ -45,8 +45,6 @@ namespace v2x rclcpp::Client::SharedPtr get_vehicle_dimensions_; rclcpp::Publisher::SharedPtr cpm_objects_pub_; rclcpp::Publisher::SharedPtr cpm_sender_pub_; - rclcpp::Publisher::SharedPtr cam_objects_pub_; - rclcpp::Publisher::SharedPtr cam_sender_pub_; double pos_lat_; double pos_lon_; diff --git a/launch/v2x.launch.xml b/launch/v2x.launch.xml index d15d223..3e20eb1 100644 --- a/launch/v2x.launch.xml +++ b/launch/v2x.launch.xml @@ -1,7 +1,7 @@ - + - + \ No newline at end of file diff --git a/src/cam_application.cpp b/src/cam_application.cpp index 015efe0..4951956 100644 --- a/src/cam_application.cpp +++ b/src/cam_application.cpp @@ -175,7 +175,9 @@ namespace v2x CoopAwareness_t &cam = message->cam; - cam.generationDeltaTime = std::chrono::duration_cast(cam_interval_).count(); + // Set GenerationTime + RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] %ld", gdt_timestamp_); + cam.generationDeltaTime = gdt_timestamp_; BasicContainer_t &basic_container = cam.camParameters.basicContainer; basic_container.stationType = StationType_passengerCar; diff --git a/src/cpm_application.cpp b/src/cpm_application.cpp index e426994..478af3d 100644 --- a/src/cpm_application.cpp +++ b/src/cpm_application.cpp @@ -32,7 +32,7 @@ using namespace vanetza; using namespace std::chrono; namespace v2x { - CpmApplication::CpmApplication(V2XNode *node, Runtime &rt, bool is_sender) : + CpmApplication::CpmApplication(V2XNode *node, Runtime &rt, bool is_sender) : node_(node), runtime_(rt), ego_(), @@ -156,7 +156,7 @@ namespace v2x { x1 = x1 / 100.0; y1 = y1 / 100.0; object.position_x = x_mgrs + (cos(orientation) * x1 - sin(orientation) * y1); - object.position_y = y_mgrs + (sin(orientation) * x1 + cos(orientation) * y1); + object.position_y = y_mgrs + (sin(orientation) * x1 + cos(orientation) * y1); object.shape_x = poc->list.array[i]->planarObjectDimension2->value; object.shape_y = poc->list.array[i]->planarObjectDimension1->value; object.shape_z = poc->list.array[i]->verticalObjectDimension->value; @@ -236,7 +236,7 @@ namespace v2x { }); if (found_object == objectsList.end()) { - + } else { found_object->to_send = true; } @@ -317,7 +317,7 @@ namespace v2x { ++cpm_object_id_; } else { - + // Object was already in internal memory // Object belongs to class person or animal @@ -327,7 +327,7 @@ namespace v2x { found_object->to_send = true; found_object->to_send_trigger = 5; } - + // Object has not been included in a CPM in the past 500 ms. if (runtime_.now().time_since_epoch().count() - found_object->timestamp.time_since_epoch().count() > 500000) { // Include all objects of class person or animal in the current CPM @@ -349,7 +349,7 @@ namespace v2x { found_object->to_send = true; found_object->to_send_trigger = 1; } else { - + } // Absolute speed changed by more than 0.5 m/s @@ -359,7 +359,7 @@ namespace v2x { if (speed > 0.5) { found_object->to_send = true; found_object->to_send_trigger = 2; - } + } // Orientation of speed vector changed by more than 4 degrees double twist_angular_x_diff = (obj.kinematics.initial_twist_with_covariance.twist.angular.x - found_object->twist_angular_x) * 180 / M_PI; @@ -434,7 +434,7 @@ namespace v2x { } else { RCLCPP_INFO(node_->get_logger(), "[objectsList] %d,,,,", cpm_num); } - + // RCLCPP_INFO(node_->get_logger(), "------------------------"); } @@ -445,7 +445,7 @@ namespace v2x { sending_ = true; printObjectsList(cpm_num_); - + // RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] Sending CPM..."); vanetza::asn1::Cpm message; @@ -578,7 +578,7 @@ namespace v2x { RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] Sending CPM with %d objects", perceivedObjectsCount); insertCpmToCpmTable(message, (char*) "cpm_sent"); - + std::unique_ptr payload{new geonet::DownPacket()}; payload->layer(OsiLayer::Application) = std::move(message); @@ -618,7 +618,7 @@ namespace v2x { } char* sql_command; - + sql_command = (char*) "create table if not exists cpm_sent(id INTEGER PRIMARY KEY, timestamp BIGINT, perceivedObjectCount INTEGER);"; ret = sqlite3_exec(db, sql_command, NULL, NULL, &err); @@ -661,7 +661,7 @@ namespace v2x { } std::stringstream sql_command; - + sql_command << "insert into " << table_name << " (timestamp, perceivedObjectCount) values (" << timestamp << ", " << perceivedObjectCount << ");"; ret = sqlite3_exec(db, sql_command.str().c_str(), NULL, NULL, &err); @@ -677,4 +677,4 @@ namespace v2x { sqlite3_close(db); // RCLCPP_INFO(node_->get_logger(), "CpmApplication::insertCpmToCpmTable Finished"); } -} \ No newline at end of file +} diff --git a/src/v2x_node.cpp b/src/v2x_node.cpp index 420a625..5b4d291 100644 --- a/src/v2x_node.cpp +++ b/src/v2x_node.cpp @@ -54,7 +54,7 @@ namespace v2x // cpm_sender_pub_ = create_publisher("/v2x/cpm/sender", rclcpp::QoS{10}); // Declare Parameters - this->declare_parameter("network_interface", "v2x_testing"); + this->declare_parameter("network_interface", "vmnet1"); this->declare_parameter("is_sender", true); // Launch V2XApp in a new thread