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:
|
||||
network_interface: "v2x_testing"
|
||||
network_interface: "wlp4s0"
|
||||
is_sender: true
|
|
@ -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,6 +37,9 @@ 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<CpmApplication::Object> *objectsStack, int cpm_num)` | |
|
||||
| `publishCpmSenderObject` | Not used now |
|
||||
|
||||
|
|
|
@ -45,8 +45,6 @@ namespace v2x
|
|||
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_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_lon_;
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
<launch>
|
||||
<arg name="network_interface" default="v2x_testing"/>
|
||||
<arg name="network_interface" default="wlp5s0"/>
|
||||
<arg name="is_sender" default="true"/>
|
||||
<node pkg="autoware_v2x" exec="autoware_v2x_node" namespace="v2x" output="screen">
|
||||
<param from="$(find-pkg-share autoware_v2x)/config/autoware_v2x.param.yaml"/>
|
||||
|
|
|
@ -175,7 +175,9 @@ namespace v2x
|
|||
|
||||
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;
|
||||
basic_container.stationType = StationType_passengerCar;
|
||||
|
|
|
@ -54,7 +54,7 @@ namespace v2x
|
|||
// cpm_sender_pub_ = create_publisher<autoware_auto_perception_msgs::msg::PredictedObjects>("/v2x/cpm/sender", rclcpp::QoS{10});
|
||||
|
||||
// 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);
|
||||
|
||||
// Launch V2XApp in a new thread
|
||||
|
|
Loading…
Reference in New Issue