Update Security module

- Using security entity v3 (from vanetza)
- Added the option to use certificates (through ros parameters)

Signed-off-by: Tiago Garcia <tiago.rgarcia@av.it.pt>
This commit is contained in:
Tiago Garcia 2024-09-04 11:19:21 +01:00
parent 7b7bb53b39
commit 90b5c22ac3
No known key found for this signature in database
GPG Key ID: A3B1096AD19E1688
6 changed files with 125 additions and 37 deletions

View File

@ -22,7 +22,7 @@ set(VANETZA_INSTALL ON)
option(BUILD_SHARED_LIBS "Build shared libraries" ON)
find_package(Vanetza REQUIRED)
find_package(GeographicLib 1.37 REQUIRED)
find_package(Boost COMPONENTS thread REQUIRED)
find_package(Boost COMPONENTS thread program_options REQUIRED)
find_package(etsi_its_cam_ts_coding REQUIRED)
find_package(etsi_its_cam_ts_conversion REQUIRED)
ament_auto_find_build_dependencies()
@ -48,7 +48,7 @@ ament_auto_add_library(autoware_v2x SHARED
src/security.cpp
)
target_link_libraries(autoware_v2x Vanetza::vanetza ${GeographicLib_LIBRARIES} Boost::thread sqlite3 etsi_its_cam_ts_coding::etsi_its_cam_ts_coding etsi_its_cam_ts_conversion::etsi_its_cam_ts_conversion)
target_link_libraries(autoware_v2x Vanetza::vanetza ${GeographicLib_LIBRARIES} Boost::thread Boost::program_options sqlite3 etsi_its_cam_ts_coding::etsi_its_cam_ts_coding etsi_its_cam_ts_conversion::etsi_its_cam_ts_conversion)
rclcpp_components_register_node(autoware_v2x
PLUGIN "v2x::V2XNode"

View File

@ -2,3 +2,8 @@
ros__parameters:
network_interface: "v2x_testing"
is_sender: true
security: "none"
certificate: ""
certificate-key: ""
certificate-chain:
- ""

View File

@ -9,7 +9,6 @@
#include <memory>
std::unique_ptr<vanetza::security::SecurityEntity>
create_security_entity(const vanetza::Runtime&, vanetza::PositionProvider&);
create_security_entity(const boost::program_options::variables_map&, const vanetza::Runtime&, vanetza::PositionProvider&);
#endif /* SECURITY_HPP_FV13ZIYA */

View File

@ -1,13 +1,27 @@
/**
* From Vanetza (https://github.com/riebl/Vanetza)
* Using Security V3
*
* https://github.com/riebl/vanetza/tree/master/vanetza/security
* https://github.com/riebl/vanetza/tree/master/tools/socktap/security.cpp
*/
#include "autoware_v2x/security.hpp"
#include <vanetza/security/certificate_cache.hpp>
#include <vanetza/security/default_certificate_validator.hpp>
#include <memory>
#include <vanetza/security/delegating_security_entity.hpp>
#include <vanetza/security/naive_certificate_provider.hpp>
#include <vanetza/security/null_certificate_validator.hpp>
#include <vanetza/security/persistence.hpp>
#include <vanetza/security/sign_header_policy.hpp>
#include <vanetza/security/static_certificate_provider.hpp>
#include <vanetza/security/trust_store.hpp>
#include <vanetza/security/straight_verify_service.hpp>
#include "vanetza/security/v2/certificate_provider.hpp"
#include <vanetza/security/v2/certificate_cache.hpp>
#include <vanetza/security/v2/default_certificate_validator.hpp>
#include <vanetza/security/v2/sign_service.hpp>
#include <vanetza/security/v3/certificate_cache.hpp>
#include <vanetza/security/v3/naive_certificate_provider.hpp>
#include <vanetza/security/v3/persistence.hpp>
#include <vanetza/security/v3/sign_header_policy.hpp>
#include <vanetza/security/v3/sign_service.hpp>
#include <vanetza/security/v3/static_certificate_provider.hpp>
#include <stdexcept>
using namespace vanetza;
@ -16,18 +30,18 @@ namespace po = boost::program_options;
class SecurityContext : public security::SecurityEntity
{
public:
SecurityContext(const Runtime &runtime, PositionProvider &positioning) : runtime(runtime), positioning(positioning),
backend(security::create_backend("default")),
sign_header_policy(runtime, positioning),
cert_cache(runtime),
cert_validator(*backend, cert_cache, trust_store)
SecurityContext(const Runtime &runtime, PositionProvider &positioning)
: runtime(runtime),
positioning(positioning),
backend(security::create_backend("default")),
sign_header_policy(runtime, positioning),
cert_cache()
{
}
security::EncapConfirm encapsulate_packet(security::EncapRequest &&request) override
{
if (!entity)
{
if (!entity) {
throw std::runtime_error("security entity is not ready");
}
return entity->encapsulate_packet(std::move(request));
@ -35,8 +49,7 @@ public:
security::DecapConfirm decapsulate_packet(security::DecapRequest &&request) override
{
if (!entity)
{
if (!entity) {
throw std::runtime_error("security entity is not ready");
}
return entity->decapsulate_packet(std::move(request));
@ -44,31 +57,78 @@ public:
void build_entity()
{
if (!cert_provider)
{
if (!cert_provider) {
throw std::runtime_error("certificate provider is missing");
}
security::SignService sign_service = straight_sign_service(*cert_provider, *backend, sign_header_policy);
security::VerifyService verify_service = straight_verify_service(runtime, *cert_provider, cert_validator,
*backend, cert_cache, sign_header_policy, positioning);
entity.reset(new security::DelegatingSecurityEntity{sign_service, verify_service});
std::unique_ptr<security::SignService> sign_service{new security::v3::StraightSignService(*cert_provider, *backend, sign_header_policy)};
std::unique_ptr<security::StraightVerifyService> verify_service{new security::StraightVerifyService(runtime, *backend, positioning)};
verify_service->use_certificate_cache(&cert_cache);
entity = std::make_unique<security::DelegatingSecurityEntity>(std::move(sign_service), std::move(verify_service));
}
const Runtime &runtime;
PositionProvider &positioning;
const Runtime & runtime;
PositionProvider & positioning;
std::unique_ptr<security::Backend> backend;
std::unique_ptr<security::SecurityEntity> entity;
std::unique_ptr<security::CertificateProvider> cert_provider;
security::DefaultSignHeaderPolicy sign_header_policy;
security::TrustStore trust_store;
security::CertificateCache cert_cache;
security::DefaultCertificateValidator cert_validator;
std::unique_ptr<security::v3::CertificateProvider> cert_provider;
security::v3::DefaultSignHeaderPolicy sign_header_policy;
security::v3::CertificateCache cert_cache;
};
std::unique_ptr<security::SecurityEntity>
create_security_entity(const Runtime &runtime, PositionProvider &positioning)
std::unique_ptr<security::v3::CertificateProvider> load_certificates(
const std::string &cert_path, const std::string &cert_key_path,
const std::vector<std::string> &cert_chain_path, security::v3::CertificateCache &cert_cache)
{
auto authorization_ticket = security::v3::load_certificate_from_file(cert_path);
auto authorization_ticket_key = security::v3::load_private_key_from_file(cert_key_path);
std::list<security::v3::Certificate> chain;
for (auto & chain_path : cert_chain_path) {
auto chain_certificate = security::v3::load_certificate_from_file(chain_path);
chain.push_back(chain_certificate);
cert_cache.store(chain_certificate);
}
return std::make_unique<security::v3::StaticCertificateProvider>(authorization_ticket, authorization_ticket_key.private_key, chain);
}
std::unique_ptr<security::SecurityEntity> create_security_entity(const po::variables_map &options, const Runtime &runtime, PositionProvider &positioning)
{
std::unique_ptr<security::SecurityEntity> security;
const std::string name = options["security"].as<std::string>();
if (name.empty() || name == "none") {
// no operation
} else if (name == "certs") {
if (options.count("certificate") ^ options.count("certificate-key")) {
throw std::runtime_error("Either certificate and certificate-key must be present or none.");
}
if (options.count("certificate") && options.count("certificate-key")) {
const auto &cert_path = options["certificate"].as<std::string>();
const auto &cert_key_path = options["certificate-key"].as<std::string>();
std::vector<std::string> chain_paths;
if (options.count("certificate-chain")) {
chain_paths = options["certificate-chain"].as<std::vector<std::string>>();
}
auto context = std::make_unique<SecurityContext>(runtime, positioning);
context->cert_provider = load_certificates(cert_path, cert_key_path, chain_paths, context->cert_cache);
context->build_entity();
security = std::move(context);
} else {
auto context = std::make_unique<SecurityContext>(runtime, positioning);
context->cert_provider = std::make_unique<security::v3::NaiveCertificateProvider>(runtime);
context->build_entity();
security = std::move(context);
}
if (!security) {
throw std::runtime_error("internal failure setting up security entity");
}
} else {
throw std::runtime_error("Unknown security entity requested");
}
return security;
}

View File

@ -24,6 +24,7 @@
#include <boost/date_time/posix_time/posix_time.hpp>
namespace gn = vanetza::geonet;
namespace po = boost::program_options;
using namespace vanetza;
using namespace std::chrono;
@ -160,7 +161,29 @@ namespace v2x
// Create raw socket on device and LinkLayer object
auto link_layer = create_link_layer(io_service, device, "ethernet");
auto positioning = create_position_provider(io_service, trigger.runtime());
auto security = create_security_entity(trigger.runtime(), *positioning);
po::variables_map security_options;
std::string entity;
std::string certificate;
std::string certificate_key;
std::vector<std::string> certificate_chain;
// Grab the values from the node parameters
node_->get_parameter("security", entity);
security_options.insert(std::make_pair("security", po::variable_value(entity, false)));
if (node_->has_parameter("certificate")) {
node_->get_parameter("certificate", certificate);
security_options.insert(std::make_pair("certificate", po::variable_value(certificate, false)));
}
if (node_->has_parameter("certificate-key")) {
node_->get_parameter("certificate-key", certificate_key);
security_options.insert(std::make_pair("certificate-key", po::variable_value(certificate_key, false)));
}
if (node_->has_parameter("certificate-chain")) {
node_->get_parameter("certificate-chain", certificate_chain);
security_options.insert(std::make_pair("certificate-chain", po::variable_value(certificate_chain, false)));
}
auto security = create_security_entity(security_options, trigger.runtime(), *positioning);
RouterContext context(mib, trigger, *positioning, security.get());
context.set_link_layer(link_layer.get());

View File

@ -58,6 +58,7 @@ namespace v2x
// Declare Parameters
this->declare_parameter<std::string>("network_interface", "v2x_testing");
this->declare_parameter<bool>("is_sender", true);
this->declare_parameter<std::string>("security", "none");
// Launch V2XApp in a new thread
app = new V2XApp(this);