Add V2XNode changes to documentation
Signed-off-by: Tiago Garcia <tiago.rgarcia@av.it.pt>
This commit is contained in:
parent
26ad12c9e0
commit
f1b160d1f7
|
@ -1,4 +1,4 @@
|
||||||
/**:
|
/**:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
network_interface: "v2x_testing"
|
network_interface: "wlp4s0"
|
||||||
is_sender: true
|
is_sender: true
|
|
@ -3,7 +3,7 @@
|
||||||
!!! Warning
|
!!! Warning
|
||||||
More to come
|
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)
|
![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
|
## 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
|
### 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 |
|
| `/perception/object_recognition/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | Perceived Objects by Autoware |
|
||||||
| `/tf` | `tf2_msgs::msg::TFMessage` | Pose of Ego Vehicle |
|
| `/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
|
### 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` |
|
| `objectsCallback(const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg)` | Call `V2XApp::objectsCallback` |
|
||||||
| `tfCallback` | Call `V2XApp::tfCallback` |
|
| `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<CpmApplication::Object> *objectsStack, int cpm_num)` | |
|
| `publishObjects(std::vector<CpmApplication::Object> *objectsStack, int cpm_num)` | |
|
||||||
| `publishCpmSenderObject` | Not used now |
|
| `publishCpmSenderObject` | Not used now |
|
||||||
|
|
||||||
|
|
||||||
## V2XApp
|
## V2XApp
|
||||||
|
|
||||||
## CPM Facility
|
## CPM Facility
|
||||||
|
|
|
@ -45,8 +45,6 @@ namespace v2x
|
||||||
rclcpp::Client<autoware_adapi_v1_msgs::srv::GetVehicleDimensions>::SharedPtr get_vehicle_dimensions_;
|
rclcpp::Client<autoware_adapi_v1_msgs::srv::GetVehicleDimensions>::SharedPtr get_vehicle_dimensions_;
|
||||||
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cpm_objects_pub_;
|
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cpm_objects_pub_;
|
||||||
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cpm_sender_pub_;
|
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cpm_sender_pub_;
|
||||||
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cam_objects_pub_;
|
|
||||||
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cam_sender_pub_;
|
|
||||||
|
|
||||||
double pos_lat_;
|
double pos_lat_;
|
||||||
double pos_lon_;
|
double pos_lon_;
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
<launch>
|
<launch>
|
||||||
<arg name="network_interface" default="v2x_testing"/>
|
<arg name="network_interface" default="wlp5s0"/>
|
||||||
<arg name="is_sender" default="true"/>
|
<arg name="is_sender" default="true"/>
|
||||||
<node pkg="autoware_v2x" exec="autoware_v2x_node" namespace="v2x" output="screen">
|
<node pkg="autoware_v2x" exec="autoware_v2x_node" namespace="v2x" output="screen">
|
||||||
<param from="$(find-pkg-share autoware_v2x)/config/autoware_v2x.param.yaml"/>
|
<param from="$(find-pkg-share autoware_v2x)/config/autoware_v2x.param.yaml"/>
|
||||||
</node>
|
</node>
|
||||||
</launch>
|
</launch>
|
|
@ -175,7 +175,9 @@ namespace v2x
|
||||||
|
|
||||||
CoopAwareness_t &cam = message->cam;
|
CoopAwareness_t &cam = message->cam;
|
||||||
|
|
||||||
cam.generationDeltaTime = std::chrono::duration_cast<std::chrono::milliseconds>(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;
|
BasicContainer_t &basic_container = cam.camParameters.basicContainer;
|
||||||
basic_container.stationType = StationType_passengerCar;
|
basic_container.stationType = StationType_passengerCar;
|
||||||
|
|
|
@ -32,7 +32,7 @@ using namespace vanetza;
|
||||||
using namespace std::chrono;
|
using namespace std::chrono;
|
||||||
|
|
||||||
namespace v2x {
|
namespace v2x {
|
||||||
CpmApplication::CpmApplication(V2XNode *node, Runtime &rt, bool is_sender) :
|
CpmApplication::CpmApplication(V2XNode *node, Runtime &rt, bool is_sender) :
|
||||||
node_(node),
|
node_(node),
|
||||||
runtime_(rt),
|
runtime_(rt),
|
||||||
ego_(),
|
ego_(),
|
||||||
|
@ -156,7 +156,7 @@ namespace v2x {
|
||||||
x1 = x1 / 100.0;
|
x1 = x1 / 100.0;
|
||||||
y1 = y1 / 100.0;
|
y1 = y1 / 100.0;
|
||||||
object.position_x = x_mgrs + (cos(orientation) * x1 - sin(orientation) * y1);
|
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_x = poc->list.array[i]->planarObjectDimension2->value;
|
||||||
object.shape_y = poc->list.array[i]->planarObjectDimension1->value;
|
object.shape_y = poc->list.array[i]->planarObjectDimension1->value;
|
||||||
object.shape_z = poc->list.array[i]->verticalObjectDimension->value;
|
object.shape_z = poc->list.array[i]->verticalObjectDimension->value;
|
||||||
|
@ -236,7 +236,7 @@ namespace v2x {
|
||||||
});
|
});
|
||||||
|
|
||||||
if (found_object == objectsList.end()) {
|
if (found_object == objectsList.end()) {
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
found_object->to_send = true;
|
found_object->to_send = true;
|
||||||
}
|
}
|
||||||
|
@ -317,7 +317,7 @@ namespace v2x {
|
||||||
++cpm_object_id_;
|
++cpm_object_id_;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
// Object was already in internal memory
|
// Object was already in internal memory
|
||||||
|
|
||||||
// Object belongs to class person or animal
|
// Object belongs to class person or animal
|
||||||
|
@ -327,7 +327,7 @@ namespace v2x {
|
||||||
found_object->to_send = true;
|
found_object->to_send = true;
|
||||||
found_object->to_send_trigger = 5;
|
found_object->to_send_trigger = 5;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Object has not been included in a CPM in the past 500 ms.
|
// 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) {
|
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
|
// 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 = true;
|
||||||
found_object->to_send_trigger = 1;
|
found_object->to_send_trigger = 1;
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Absolute speed changed by more than 0.5 m/s
|
// Absolute speed changed by more than 0.5 m/s
|
||||||
|
@ -359,7 +359,7 @@ namespace v2x {
|
||||||
if (speed > 0.5) {
|
if (speed > 0.5) {
|
||||||
found_object->to_send = true;
|
found_object->to_send = true;
|
||||||
found_object->to_send_trigger = 2;
|
found_object->to_send_trigger = 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Orientation of speed vector changed by more than 4 degrees
|
// 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;
|
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 {
|
} else {
|
||||||
RCLCPP_INFO(node_->get_logger(), "[objectsList] %d,,,,", cpm_num);
|
RCLCPP_INFO(node_->get_logger(), "[objectsList] %d,,,,", cpm_num);
|
||||||
}
|
}
|
||||||
|
|
||||||
// RCLCPP_INFO(node_->get_logger(), "------------------------");
|
// RCLCPP_INFO(node_->get_logger(), "------------------------");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -445,7 +445,7 @@ namespace v2x {
|
||||||
sending_ = true;
|
sending_ = true;
|
||||||
|
|
||||||
printObjectsList(cpm_num_);
|
printObjectsList(cpm_num_);
|
||||||
|
|
||||||
// RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] Sending CPM...");
|
// RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] Sending CPM...");
|
||||||
|
|
||||||
vanetza::asn1::Cpm message;
|
vanetza::asn1::Cpm message;
|
||||||
|
@ -578,7 +578,7 @@ namespace v2x {
|
||||||
RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] Sending CPM with %d objects", perceivedObjectsCount);
|
RCLCPP_INFO(node_->get_logger(), "[CpmApplication::send] Sending CPM with %d objects", perceivedObjectsCount);
|
||||||
|
|
||||||
insertCpmToCpmTable(message, (char*) "cpm_sent");
|
insertCpmToCpmTable(message, (char*) "cpm_sent");
|
||||||
|
|
||||||
std::unique_ptr<geonet::DownPacket> payload{new geonet::DownPacket()};
|
std::unique_ptr<geonet::DownPacket> payload{new geonet::DownPacket()};
|
||||||
|
|
||||||
payload->layer(OsiLayer::Application) = std::move(message);
|
payload->layer(OsiLayer::Application) = std::move(message);
|
||||||
|
@ -618,7 +618,7 @@ namespace v2x {
|
||||||
}
|
}
|
||||||
|
|
||||||
char* sql_command;
|
char* sql_command;
|
||||||
|
|
||||||
sql_command = (char*) "create table if not exists cpm_sent(id INTEGER PRIMARY KEY, timestamp BIGINT, perceivedObjectCount INTEGER);";
|
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);
|
ret = sqlite3_exec(db, sql_command, NULL, NULL, &err);
|
||||||
|
@ -661,7 +661,7 @@ namespace v2x {
|
||||||
}
|
}
|
||||||
|
|
||||||
std::stringstream sql_command;
|
std::stringstream sql_command;
|
||||||
|
|
||||||
sql_command << "insert into " << table_name << " (timestamp, perceivedObjectCount) values (" << timestamp << ", " << perceivedObjectCount << ");";
|
sql_command << "insert into " << table_name << " (timestamp, perceivedObjectCount) values (" << timestamp << ", " << perceivedObjectCount << ");";
|
||||||
|
|
||||||
ret = sqlite3_exec(db, sql_command.str().c_str(), NULL, NULL, &err);
|
ret = sqlite3_exec(db, sql_command.str().c_str(), NULL, NULL, &err);
|
||||||
|
@ -677,4 +677,4 @@ namespace v2x {
|
||||||
sqlite3_close(db);
|
sqlite3_close(db);
|
||||||
// RCLCPP_INFO(node_->get_logger(), "CpmApplication::insertCpmToCpmTable Finished");
|
// RCLCPP_INFO(node_->get_logger(), "CpmApplication::insertCpmToCpmTable Finished");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -54,7 +54,7 @@ namespace v2x
|
||||||
// cpm_sender_pub_ = create_publisher<autoware_auto_perception_msgs::msg::PredictedObjects>("/v2x/cpm/sender", rclcpp::QoS{10});
|
// cpm_sender_pub_ = create_publisher<autoware_auto_perception_msgs::msg::PredictedObjects>("/v2x/cpm/sender", rclcpp::QoS{10});
|
||||||
|
|
||||||
// Declare Parameters
|
// Declare Parameters
|
||||||
this->declare_parameter<std::string>("network_interface", "v2x_testing");
|
this->declare_parameter<std::string>("network_interface", "vmnet1");
|
||||||
this->declare_parameter<bool>("is_sender", true);
|
this->declare_parameter<bool>("is_sender", true);
|
||||||
|
|
||||||
// Launch V2XApp in a new thread
|
// Launch V2XApp in a new thread
|
||||||
|
|
Loading…
Reference in New Issue