2021-11-10 15:21:32 +00:00
|
|
|
#ifndef V2X_NODE_HPP_EUIC2VFR
|
|
|
|
#define V2X_NODE_HPP_EUIC2VFR
|
|
|
|
|
2021-10-27 21:56:21 +00:00
|
|
|
#include "rclcpp/rclcpp.hpp"
|
|
|
|
#include "std_msgs/msg/string.hpp"
|
2022-03-28 02:17:51 +00:00
|
|
|
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
|
2024-06-12 22:51:59 +00:00
|
|
|
#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp"
|
2024-07-09 13:54:53 +00:00
|
|
|
#include "autoware_adapi_v1_msgs/msg/vehicle_status.hpp"
|
2021-10-27 21:56:21 +00:00
|
|
|
#include "tf2_msgs/msg/tf_message.hpp"
|
|
|
|
#include <boost/asio/io_service.hpp>
|
2021-11-10 08:14:09 +00:00
|
|
|
#include "autoware_v2x/v2x_app.hpp"
|
2021-10-27 21:56:21 +00:00
|
|
|
#include "autoware_v2x/cpm_application.hpp"
|
2024-06-12 22:51:59 +00:00
|
|
|
#include "autoware_v2x/cam_application.hpp"
|
2021-10-27 21:56:21 +00:00
|
|
|
#include "autoware_v2x/time_trigger.hpp"
|
|
|
|
#include "autoware_v2x/link_layer.hpp"
|
|
|
|
#include "autoware_v2x/ethernet_device.hpp"
|
|
|
|
#include "autoware_v2x/positioning.hpp"
|
|
|
|
#include "autoware_v2x/security.hpp"
|
|
|
|
#include "autoware_v2x/router_context.hpp"
|
2022-07-21 00:12:24 +00:00
|
|
|
#include <fstream>
|
2021-10-27 21:56:21 +00:00
|
|
|
|
|
|
|
namespace v2x
|
|
|
|
{
|
|
|
|
class V2XNode : public rclcpp::Node
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
explicit V2XNode(const rclcpp::NodeOptions &node_options);
|
2021-11-10 08:14:09 +00:00
|
|
|
V2XApp *app;
|
2022-07-21 00:12:24 +00:00
|
|
|
void publishObjects(std::vector<CpmApplication::Object> *, int cpm_num);
|
2022-05-19 11:00:02 +00:00
|
|
|
void publishCpmSenderObject(double, double, double);
|
2024-07-08 10:08:49 +00:00
|
|
|
|
2022-07-21 00:12:24 +00:00
|
|
|
std::ofstream latency_log_file;
|
|
|
|
|
2021-10-27 21:56:21 +00:00
|
|
|
private:
|
2022-03-28 02:17:51 +00:00
|
|
|
void objectsCallback(const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
|
2024-06-12 22:51:59 +00:00
|
|
|
void velocityReportCallback(const autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr msg);
|
2024-07-09 13:54:53 +00:00
|
|
|
void vehicleStatucCallback(const autoware_adapi_v1_msgs::msg::VehicleStatus::ConstSharedPtr msg);
|
2024-07-08 10:08:49 +00:00
|
|
|
void getVehicleDimensions();
|
2021-10-27 21:56:21 +00:00
|
|
|
void tfCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr msg);
|
|
|
|
|
2022-10-31 09:51:20 +00:00
|
|
|
rclcpp::Subscription<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr objects_sub_;
|
2024-06-12 22:51:59 +00:00
|
|
|
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr velocity_report_sub_;
|
2024-07-09 13:54:53 +00:00
|
|
|
rclcpp::Subscription<autoware_adapi_v1_msgs::msg::VehicleStatus>::SharedPtr vehicle_status_sub_;
|
2022-10-31 09:51:20 +00:00
|
|
|
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr tf_sub_;
|
2024-07-08 10:08:49 +00:00
|
|
|
rclcpp::Client<autoware_adapi_v1_msgs::srv::GetVehicleDimensions>::SharedPtr get_vehicle_dimensions_;
|
2022-10-31 09:51:20 +00:00
|
|
|
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cpm_objects_pub_;
|
|
|
|
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cpm_sender_pub_;
|
2024-06-12 22:51:59 +00:00
|
|
|
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cam_objects_pub_;
|
|
|
|
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr cam_sender_pub_;
|
2021-10-27 21:56:21 +00:00
|
|
|
|
|
|
|
double pos_lat_;
|
|
|
|
double pos_lon_;
|
|
|
|
};
|
2021-11-10 15:21:32 +00:00
|
|
|
}
|
|
|
|
|
2024-07-08 10:08:49 +00:00
|
|
|
#endif
|