2021-11-10 08:13:32 +00:00
|
|
|
#ifndef V2X_APP_HPP_EUIC2VFR
|
|
|
|
#define V2X_APP_HPP_EUIC2VFR
|
|
|
|
|
|
|
|
#include "rclcpp/rclcpp.hpp"
|
|
|
|
#include "std_msgs/msg/string.hpp"
|
|
|
|
#include "autoware_perception_msgs/msg/dynamic_object_array.hpp"
|
|
|
|
#include "tf2_msgs/msg/tf_message.hpp"
|
|
|
|
#include <boost/asio/io_service.hpp>
|
|
|
|
#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"
|
2021-11-10 15:21:32 +00:00
|
|
|
// #include "autoware_v2x/v2x_node.hpp"
|
2021-11-10 08:13:32 +00:00
|
|
|
|
|
|
|
namespace v2x
|
|
|
|
{
|
2021-11-10 15:21:32 +00:00
|
|
|
class V2XNode;
|
2021-11-10 08:13:32 +00:00
|
|
|
class V2XApp
|
|
|
|
{
|
|
|
|
public:
|
2021-11-10 15:21:32 +00:00
|
|
|
V2XApp(V2XNode *);
|
2021-11-10 08:13:32 +00:00
|
|
|
void start();
|
|
|
|
void objectsCallback(const autoware_perception_msgs::msg::DynamicObjectArray::ConstSharedPtr);
|
|
|
|
void tfCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr);
|
|
|
|
|
|
|
|
CpmApplication *cp;
|
2021-11-10 15:21:32 +00:00
|
|
|
// V2XNode *v2x_node;
|
2021-11-10 08:13:32 +00:00
|
|
|
|
|
|
|
private:
|
|
|
|
friend class CpmApplication;
|
|
|
|
friend class Application;
|
2021-11-10 15:21:32 +00:00
|
|
|
V2XNode* node_;
|
2021-11-10 08:13:32 +00:00
|
|
|
bool tf_received_;
|
|
|
|
bool cp_started_;
|
|
|
|
};
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif
|