Go to the documentation of this file.
54 #include <etsi_its_mapem_ts_msgs/LaneAttributes.h>
55 namespace mapem_ts_msgs = etsi_its_mapem_ts_msgs;
57 #include <etsi_its_mapem_ts_msgs/msg/lane_attributes.hpp>
58 namespace mapem_ts_msgs = etsi_its_mapem_ts_msgs::msg;
mapem_ts_LaneDirection_t directionalUse
mapem_ts_LaneSharing_t sharedWith
void toRos_LaneTypeAttributes(const mapem_ts_LaneTypeAttributes_t &in, mapem_ts_msgs::LaneTypeAttributes &out)
void toStruct_LaneSharing(const mapem_ts_msgs::LaneSharing &in, mapem_ts_LaneSharing_t &out)
void toRos_LaneSharing(const mapem_ts_LaneSharing_t &in, mapem_ts_msgs::LaneSharing &out)
mapem_ts_LaneTypeAttributes_t laneType
void toRos_LaneDirection(const mapem_ts_LaneDirection_t &in, mapem_ts_msgs::LaneDirection &out)
void toStruct_LaneDirection(const mapem_ts_msgs::LaneDirection &in, mapem_ts_LaneDirection_t &out)
void toStruct_LaneAttributes(const mapem_ts_msgs::LaneAttributes &in, mapem_ts_LaneAttributes_t &out)
void toStruct_LaneTypeAttributes(const mapem_ts_msgs::LaneTypeAttributes &in, mapem_ts_LaneTypeAttributes_t &out)
void toRos_LaneAttributes(const mapem_ts_LaneAttributes_t &in, mapem_ts_msgs::LaneAttributes &out)