AutowareV2X/include/autoware_v2x/v2x_node.hpp

42 lines
1.5 KiB
C++
Raw Normal View History

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"
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"
#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"
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;
2021-11-10 15:21:32 +00:00
void publishObjects(std::vector<CpmApplication::Object> *);
void publishCpmSenderObject(double, double, double);
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);
2021-10-27 21:56:21 +00:00
void tfCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr msg);
2022-03-28 02:17:51 +00:00
rclcpp::Subscription<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr subscription_;
2021-10-27 21:56:21 +00:00
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr subscription_pos_;
2022-03-28 02:17:51 +00:00
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr publisher_;
rclcpp::Publisher<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr publisher_v2x_cpm_sender_;
2021-10-27 21:56:21 +00:00
double pos_lat_;
double pos_lon_;
};
2021-11-10 15:21:32 +00:00
}
#endif