2021-11-01 07:26:45 +00:00
|
|
|
#include "autoware_v2x/v2x_node.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/time_trigger.hpp"
|
|
|
|
#include "autoware_v2x/router_context.hpp"
|
|
|
|
#include "autoware_v2x/positioning.hpp"
|
|
|
|
#include "autoware_v2x/security.hpp"
|
|
|
|
#include "autoware_v2x/link_layer.hpp"
|
|
|
|
#include "autoware_v2x/cpm_application.hpp"
|
|
|
|
|
|
|
|
#include "rclcpp/rclcpp.hpp"
|
|
|
|
#include "std_msgs/msg/string.hpp"
|
|
|
|
|
|
|
|
#include <vanetza/asn1/cpm.hpp>
|
|
|
|
#include <vanetza/facilities/cpm_functions.hpp>
|
|
|
|
#include <sstream>
|
|
|
|
#include <memory>
|
|
|
|
#include <boost/thread.hpp>
|
2021-11-10 08:14:09 +00:00
|
|
|
#include <boost/date_time/posix_time/posix_time.hpp>
|
2021-10-27 21:56:21 +00:00
|
|
|
|
2022-05-19 11:00:02 +00:00
|
|
|
#include "tf2/LinearMath/Quaternion.h"
|
|
|
|
|
2021-10-27 21:56:21 +00:00
|
|
|
namespace gn = vanetza::geonet;
|
|
|
|
|
|
|
|
using namespace vanetza;
|
|
|
|
using namespace vanetza::facilities;
|
|
|
|
using namespace std::chrono;
|
|
|
|
|
|
|
|
namespace v2x
|
|
|
|
{
|
2022-01-15 07:14:17 +00:00
|
|
|
V2XNode::V2XNode(const rclcpp::NodeOptions &node_options) : rclcpp::Node("autoware_v2x_node", node_options) {
|
2021-10-27 21:56:21 +00:00
|
|
|
using std::placeholders::_1;
|
2022-03-28 02:17:51 +00:00
|
|
|
subscription_ = this->create_subscription<autoware_auto_perception_msgs::msg::PredictedObjects>("/perception/object_recognition/objects", 10, std::bind(&V2XNode::objectsCallback, this, _1));
|
2021-10-27 21:56:21 +00:00
|
|
|
|
|
|
|
subscription_pos_ = this->create_subscription<tf2_msgs::msg::TFMessage>("/tf", 10, std::bind(&V2XNode::tfCallback, this, _1));
|
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
publisher_ = create_publisher<autoware_auto_perception_msgs::msg::PredictedObjects>("/v2x/cpm/objects", rclcpp::QoS{10});
|
2022-05-19 11:00:02 +00:00
|
|
|
publisher_v2x_cpm_sender_ = create_publisher<autoware_auto_perception_msgs::msg::PredictedObjects>("/v2x/cpm/sender", rclcpp::QoS{10});
|
2021-10-27 21:56:21 +00:00
|
|
|
|
2021-12-08 11:33:06 +00:00
|
|
|
this->declare_parameter<std::string>("network_interface", "vmnet1");
|
2022-02-27 03:26:11 +00:00
|
|
|
this->declare_parameter<bool>("is_sender", true);
|
2021-12-08 11:33:06 +00:00
|
|
|
|
2021-11-10 08:14:09 +00:00
|
|
|
app = new V2XApp(this);
|
|
|
|
boost::thread v2xApp(boost::bind(&V2XApp::start, app));
|
2021-10-27 21:56:21 +00:00
|
|
|
|
2021-11-10 15:21:32 +00:00
|
|
|
RCLCPP_INFO(get_logger(), "V2X Node Launched");
|
2022-01-15 07:14:17 +00:00
|
|
|
|
|
|
|
rclcpp::Time current_time = this->now();
|
|
|
|
RCLCPP_INFO(get_logger(), "[V2XNode::V2XNode] [measure] T_R1 %ld", current_time.nanoseconds());
|
|
|
|
|
2021-11-10 15:21:32 +00:00
|
|
|
}
|
|
|
|
|
2022-05-19 11:00:02 +00:00
|
|
|
void V2XNode::publishCpmSenderObject(double x_mgrs, double y_mgrs, double orientation) {
|
|
|
|
autoware_auto_perception_msgs::msg::PredictedObjects cpm_sender_object_msg;
|
|
|
|
std_msgs::msg::Header header;
|
|
|
|
rclcpp::Time current_time = this->now();
|
|
|
|
cpm_sender_object_msg.header.frame_id = "map";
|
|
|
|
cpm_sender_object_msg.header.stamp = current_time;
|
|
|
|
|
|
|
|
autoware_auto_perception_msgs::msg::PredictedObject object;
|
|
|
|
autoware_auto_perception_msgs::msg::ObjectClassification classification;
|
|
|
|
autoware_auto_perception_msgs::msg::Shape shape;
|
|
|
|
autoware_auto_perception_msgs::msg::PredictedObjectKinematics kinematics;
|
|
|
|
|
|
|
|
classification.label = autoware_auto_perception_msgs::msg::ObjectClassification::CAR;
|
|
|
|
classification.probability = 0.99;
|
|
|
|
|
|
|
|
shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX;
|
|
|
|
shape.dimensions.x = 5.0;
|
|
|
|
shape.dimensions.y = 2.0;
|
|
|
|
shape.dimensions.z = 1.7;
|
|
|
|
|
|
|
|
kinematics.initial_pose_with_covariance.pose.position.x = x_mgrs;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.position.y = y_mgrs;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.position.z = 0.1;
|
|
|
|
|
|
|
|
tf2::Quaternion quat;
|
|
|
|
quat.setRPY(0, 0, orientation);
|
|
|
|
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.x = quat.x();
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.y = quat.y();
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.z = quat.z();
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.w = quat.w();
|
|
|
|
|
|
|
|
object.classification.emplace_back(classification);
|
|
|
|
object.shape = shape;
|
|
|
|
object.kinematics = kinematics;
|
|
|
|
|
|
|
|
cpm_sender_object_msg.objects.push_back(object);
|
|
|
|
|
|
|
|
publisher_v2x_cpm_sender_->publish(cpm_sender_object_msg);
|
|
|
|
|
|
|
|
}
|
|
|
|
|
2021-11-10 15:21:32 +00:00
|
|
|
void V2XNode::publishObjects(std::vector<CpmApplication::Object> *objectsStack) {
|
2022-03-28 02:17:51 +00:00
|
|
|
autoware_auto_perception_msgs::msg::PredictedObjects output_dynamic_object_msg;
|
2021-11-10 15:21:32 +00:00
|
|
|
std_msgs::msg::Header header;
|
|
|
|
rclcpp::Time current_time = this->now();
|
|
|
|
output_dynamic_object_msg.header.frame_id = "map";
|
|
|
|
output_dynamic_object_msg.header.stamp = current_time;
|
|
|
|
|
|
|
|
for (CpmApplication::Object obj : *objectsStack) {
|
2022-03-28 02:17:51 +00:00
|
|
|
autoware_auto_perception_msgs::msg::PredictedObject object;
|
|
|
|
autoware_auto_perception_msgs::msg::ObjectClassification classification;
|
|
|
|
autoware_auto_perception_msgs::msg::Shape shape;
|
|
|
|
autoware_auto_perception_msgs::msg::PredictedObjectKinematics kinematics;
|
2021-11-10 15:21:32 +00:00
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
classification.label = autoware_auto_perception_msgs::msg::ObjectClassification::CAR;
|
|
|
|
classification.probability = 0.99;
|
2021-11-10 15:21:32 +00:00
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX;
|
2021-11-17 12:01:38 +00:00
|
|
|
shape.dimensions.x = obj.shape_x / 10.0;
|
|
|
|
shape.dimensions.y = obj.shape_y / 10.0;
|
|
|
|
shape.dimensions.z = obj.shape_z / 10.0;
|
2021-11-10 15:21:32 +00:00
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
kinematics.initial_pose_with_covariance.pose.position.x = obj.position_x;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.position.y = obj.position_y;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.position.z = 0.1;
|
2021-11-14 04:26:18 +00:00
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.x = obj.orientation_x;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.y = obj.orientation_y;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.z = obj.orientation_z;
|
|
|
|
kinematics.initial_pose_with_covariance.pose.orientation.w = obj.orientation_w;
|
2021-11-10 15:21:32 +00:00
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
object.classification.emplace_back(classification);
|
2021-11-10 15:21:32 +00:00
|
|
|
object.shape = shape;
|
2022-03-28 02:17:51 +00:00
|
|
|
object.kinematics = kinematics;
|
2021-11-10 15:21:32 +00:00
|
|
|
|
|
|
|
output_dynamic_object_msg.objects.push_back(object);
|
|
|
|
}
|
2022-01-15 07:14:17 +00:00
|
|
|
|
|
|
|
current_time = this->now();
|
2022-02-27 03:26:11 +00:00
|
|
|
// RCLCPP_INFO(get_logger(), "[V2XNode::publishObjects] [measure] T_obj_r2 %ld", current_time.nanoseconds());
|
2022-01-15 07:14:17 +00:00
|
|
|
|
2021-11-10 15:21:32 +00:00
|
|
|
publisher_->publish(output_dynamic_object_msg);
|
2021-10-27 21:56:21 +00:00
|
|
|
}
|
|
|
|
|
2022-03-28 02:17:51 +00:00
|
|
|
void V2XNode::objectsCallback(const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg) {
|
2021-11-10 15:21:32 +00:00
|
|
|
rclcpp::Time current_time = this->now();
|
2022-01-15 07:14:17 +00:00
|
|
|
rclcpp::Time msg_time = msg->header.stamp; // timestamp included in the Autoware Perception Msg.
|
2022-02-27 03:26:11 +00:00
|
|
|
// RCLCPP_INFO(get_logger(), "[V2XNode::objectsCallback] %d objects", msg->objects.size());
|
2022-01-15 07:14:17 +00:00
|
|
|
|
|
|
|
// Measuring T_A1R1
|
2022-02-27 03:26:11 +00:00
|
|
|
// RCLCPP_INFO(get_logger(), "[V2XNode::objectsCallback] [measure] T_obj %ld", msg_time.nanoseconds());
|
|
|
|
// RCLCPP_INFO(get_logger(), "[V2XNode::objectsCallback] [measure] T_obj_receive %ld", current_time.nanoseconds());
|
2022-01-15 07:14:17 +00:00
|
|
|
app->objectsCallback(msg);
|
2021-10-27 21:56:21 +00:00
|
|
|
}
|
|
|
|
|
2022-01-15 07:14:17 +00:00
|
|
|
void V2XNode::tfCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr msg) {
|
2021-11-10 08:14:09 +00:00
|
|
|
app->tfCallback(msg);
|
2021-10-27 21:56:21 +00:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
#include "rclcpp_components/register_node_macro.hpp"
|
|
|
|
RCLCPP_COMPONENTS_REGISTER_NODE(v2x::V2XNode)
|