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 <external_object_list_to_sdsm_component.hpp>
Public Member Functions | |
ExternalObjectListToSdsmNode (const rclcpp::NodeOptions &options) | |
auto | handle_on_configure (const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override |
auto | handle_on_cleanup (const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override |
auto | handle_on_shutdown (const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override |
auto | publish_as_sdsm (const external_objects_msg_type &msg) const -> void |
auto | update_georeference (const georeference_msg_type &proj_string) -> void |
auto | update_current_pose (const pose_msg_type &pose) -> void |
Private Types | |
using | sdsm_msg_type = carma_v2x_msgs::msg::SensorDataSharingMessage |
using | external_objects_msg_type = carma_perception_msgs::msg::ExternalObjectList |
using | georeference_msg_type = std_msgs::msg::String |
using | pose_msg_type = geometry_msgs::msg::PoseStamped |
Private Attributes | |
rclcpp_lifecycle::LifecyclePublisher< sdsm_msg_type >::SharedPtr | sdsm_publisher_ {nullptr} |
rclcpp::Subscription< external_objects_msg_type >::SharedPtr | external_objects_subscription_ |
rclcpp::Subscription< georeference_msg_type >::SharedPtr | georeference_subscription_ {nullptr} |
rclcpp::Subscription< pose_msg_type >::SharedPtr | current_pose_subscription_ {nullptr} |
std::string | map_georeference_ {""} |
geometry_msgs::msg::PoseStamped | current_pose_ |
std::shared_ptr< lanelet::projection::LocalFrameProjector > | map_projector_ {nullptr} |
OnSetParametersCallbackHandle::SharedPtr | on_set_parameters_callback_ {nullptr} |
Definition at line 34 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 37 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 38 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 40 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 36 of file external_object_list_to_sdsm_component.hpp.
|
explicit |
Definition at line 25 of file external_object_list_to_sdsm_component.cpp.
References on_set_parameters_callback_, and sdsm_publisher_.
|
override |
Definition at line 90 of file external_object_list_to_sdsm_component.cpp.
|
override |
Definition at line 32 of file external_object_list_to_sdsm_component.cpp.
|
override |
Definition at line 104 of file external_object_list_to_sdsm_component.cpp.
auto carma_cooperative_perception::ExternalObjectListToSdsmNode::publish_as_sdsm | ( | const external_objects_msg_type & | msg | ) | const -> void |
Definition at line 118 of file external_object_list_to_sdsm_component.cpp.
References carma_cooperative_perception::to_sdsm_msg().
auto carma_cooperative_perception::ExternalObjectListToSdsmNode::update_current_pose | ( | const pose_msg_type & | pose | ) | -> void |
Definition at line 149 of file external_object_list_to_sdsm_component.cpp.
auto carma_cooperative_perception::ExternalObjectListToSdsmNode::update_georeference | ( | const georeference_msg_type & | proj_string | ) | -> void |
Definition at line 140 of file external_object_list_to_sdsm_component.cpp.
|
private |
Definition at line 68 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 65 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 62 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 64 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 67 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 70 of file external_object_list_to_sdsm_component.hpp.
|
private |
Definition at line 71 of file external_object_list_to_sdsm_component.hpp.
Referenced by ExternalObjectListToSdsmNode().
|
private |
Definition at line 61 of file external_object_list_to_sdsm_component.hpp.
Referenced by ExternalObjectListToSdsmNode().