Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
|
#include "carma_cooperative_perception/msg_conversion.hpp"
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <carma_cooperative_perception_interfaces/msg/track.hpp>
#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_perception_msgs/msg/external_object_list.hpp>
#include <j2735_v2x_msgs/msg/d_date_time.hpp>
#include <j2735_v2x_msgs/msg/personal_device_user_type.hpp>
#include <j2735_v2x_msgs/to_floating_point.hpp>
#include <j3224_v2x_msgs/msg/detected_object_data.hpp>
#include <j3224_v2x_msgs/msg/measurement_time_offset.hpp>
#include <j3224_v2x_msgs/msg/object_type.hpp>
#include <j2735_v2x_msgs/msg/positional_accuracy.hpp>
#include <j3224_v2x_msgs/msg/equipment_type.hpp>
#include <algorithm>
#include <cctype>
#include <charconv>
#include <chrono>
#include <cmath>
#include <limits>
#include <numeric>
#include <string>
#include <utility>
#include <proj.h>
#include <gsl/pointers>
#include <memory>
#include "carma_cooperative_perception/geodetic.hpp"
#include "carma_cooperative_perception/j2735_types.hpp"
#include "carma_cooperative_perception/j3224_types.hpp"
#include "carma_cooperative_perception/units_extensions.hpp"
#include <lanelet2_core/geometry/Lanelet.h>
#include <lanelet2_extension/projection/local_frame_projector.h>
#include <boost/date_time/posix_time/conversion.hpp>
#include <boost/date_time/posix_time/posix_time_io.hpp>
#include "boost/date_time/posix_time/posix_time.hpp"
Go to the source code of this file.
Namespaces | |
namespace | carma_cooperative_perception |
Functions | |
auto | carma_cooperative_perception::to_time_msg (const DDateTime &d_date_time) -> builtin_interfaces::msg::Time |
auto | carma_cooperative_perception::calc_detection_time_stamp (DDateTime d_date_time, const MeasurementTimeOffset &offset) -> DDateTime |
auto | carma_cooperative_perception::ned_to_enu (const PositionOffsetXYZ &offset_ned) noexcept |
auto | carma_cooperative_perception::to_ddate_time_msg (const builtin_interfaces::msg::Time &builtin_time) -> j2735_v2x_msgs::msg::DDateTime |
auto | carma_cooperative_perception::calc_sdsm_time_offset (const builtin_interfaces::msg::Time &external_object_list_time, const builtin_interfaces::msg::Time &external_object_time) -> carma_v2x_msgs::msg::MeasurementTimeOffset |
auto | carma_cooperative_perception::to_position_msg (const UtmCoordinate &position_utm) -> geometry_msgs::msg::Point |
auto | carma_cooperative_perception::to_position_msg (const MapCoordinate &position_map) -> geometry_msgs::msg::Point |
auto | carma_cooperative_perception::heading_to_enu_yaw (const units::angle::degree_t &heading) -> units::angle::degree_t |
auto | carma_cooperative_perception::enu_orientation_to_true_heading (double yaw, const lanelet::BasicPoint3d &obj_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> units::angle::degree_t |
auto | carma_cooperative_perception::calc_relative_position (const geometry_msgs::msg::PoseStamped ¤t_pose, const carma_v2x_msgs::msg::PositionOffsetXYZ &detected_object_data) -> carma_v2x_msgs::msg::PositionOffsetXYZ |
auto | carma_cooperative_perception::transform_pose_from_map_to_wgs84 (const geometry_msgs::msg::PoseStamped &source_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::Position3D |
auto | carma_cooperative_perception::to_detection_list_msg (const carma_v2x_msgs::msg::SensorDataSharingMessage &sdsm, std::string_view georeference) -> carma_cooperative_perception_interfaces::msg::DetectionList |
auto | carma_cooperative_perception::to_detection_msg (const carma_perception_msgs::msg::ExternalObject &object, const MotionModelMapping &motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::Detection |
auto | carma_cooperative_perception::to_detection_list_msg (const carma_perception_msgs::msg::ExternalObjectList &object_list, const MotionModelMapping &motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::DetectionList |
auto | carma_cooperative_perception::to_external_object_msg (const carma_cooperative_perception_interfaces::msg::Track &track) -> carma_perception_msgs::msg::ExternalObject |
auto | carma_cooperative_perception::to_external_object_list_msg (const carma_cooperative_perception_interfaces::msg::TrackList &track_list) -> carma_perception_msgs::msg::ExternalObjectList |
auto | carma_cooperative_perception::to_sdsm_msg (const carma_perception_msgs::msg::ExternalObjectList &external_object_list, const geometry_msgs::msg::PoseStamped ¤t_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::SensorDataSharingMessage |
auto | carma_cooperative_perception::to_detected_object_data_msg (const carma_perception_msgs::msg::ExternalObject &external_object, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::DetectedObjectData |