AutowareV2X/include/autoware_v2x/v2x_app.hpp

54 lines
1.7 KiB
C++
Raw Normal View History

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"
2022-03-28 02:17:51 +00:00
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp"
#include "autoware_auto_vehicle_msgs/msg/gear_report.hpp"
#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp"
2021-11-10 08:13:32 +00:00
#include "tf2_msgs/msg/tf_message.hpp"
#include <boost/asio/io_service.hpp>
#include "autoware_v2x/cpm_application.hpp"
#include "autoware_v2x/cam_application.hpp"
2021-11-10 08:13:32 +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"
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();
2022-03-28 02:17:51 +00:00
void objectsCallback(const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr);
void velocityReportCallback(const autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr);
void gearReportCallback(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr);
void steeringReportCallback(const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr);
2021-11-10 08:13:32 +00:00
void tfCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr);
CpmApplication *cp;
CamApplication *cam;
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 CamApplication;
2021-11-10 08:13:32 +00:00
friend class Application;
2021-11-10 15:21:32 +00:00
V2XNode* node_;
2021-11-10 08:13:32 +00:00
bool tf_received_;
2021-11-10 20:30:21 +00:00
int tf_interval_;
bool vehicle_dimensions_set_;
2021-11-10 08:13:32 +00:00
bool cp_started_;
bool cam_started_;
2021-11-10 08:13:32 +00:00
};
}
#endif