#include <mrpt/core/WorkerThreadsPool.h>
#include <mrpt/obs/CObservation.h>
#include <mrpt/obs/CObservation3DRangeScan.h>
#include <mrpt/obs/CObservationGPS.h>
#include <mrpt/obs/CObservationIMU.h>
#include <mrpt/obs/CObservationPointCloud.h>
#include <mrpt/system/CTicTac.h>
#include <mrpt/system/CTimeLogger.h>
#include <mvsim/World.h>
#include <tf2/LinearMath/Transform.h>
#include <atomic>
#include <thread>
#include <geometry_msgs/msg/polygon.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <nav_msgs/msg/map_meta_data.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/clock.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/time_source.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <std_msgs/msg/bool.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
#include "wrapper/publisher_wrapper.h"
Go to the source code of this file.
Classes | |
class | MVSimNode |
struct | MVSimNode::TPubSubPerVehicle |
struct | MVSimNode::TThreadParams |
struct | MVSimNode::WorldPubs |
Namespaces | |
mvsim_node | |
Typedefs | |
using | Msg_Bool = std_msgs::msg::Bool |
using | Msg_CameraInfo = sensor_msgs::msg::CameraInfo |
using | Msg_MapMetaData = nav_msgs::msg::MapMetaData |
using | Msg_MarkerArray = visualization_msgs::msg::MarkerArray |
using | Msg_OccupancyGrid = nav_msgs::msg::OccupancyGrid |
using | Msg_Odometry = nav_msgs::msg::Odometry |
using | Msg_Polygon = geometry_msgs::msg::Polygon |
using | Msg_PoseArray = geometry_msgs::msg::PoseArray |
using | Msg_PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped |
using | Msg_TFMessage = tf2_msgs::msg::TFMessage |
using | Msg_Twist = geometry_msgs::msg::Twist |
using | Msg_Twist_CSPtr = geometry_msgs::msg::Twist::ConstSharedPtr |
using | ros_Duration = rclcpp::Duration |
using | ros_Time = rclcpp::Time |
template<typename T > | |
using | mvsim_node::shared_ptr = std::shared_ptr< T > |
Functions | |
template<typename T , typename... Args> | |
std::shared_ptr< T > | mvsim_node::make_shared (Args &&... args) |
using Msg_Bool = std_msgs::msg::Bool |
Definition at line 94 of file mvsim_node_core.h.
using Msg_CameraInfo = sensor_msgs::msg::CameraInfo |
Definition at line 97 of file mvsim_node_core.h.
using Msg_MapMetaData = nav_msgs::msg::MapMetaData |
Definition at line 93 of file mvsim_node_core.h.
using Msg_MarkerArray = visualization_msgs::msg::MarkerArray |
Definition at line 96 of file mvsim_node_core.h.
using Msg_OccupancyGrid = nav_msgs::msg::OccupancyGrid |
Definition at line 91 of file mvsim_node_core.h.
using Msg_Odometry = nav_msgs::msg::Odometry |
Definition at line 92 of file mvsim_node_core.h.
using Msg_Polygon = geometry_msgs::msg::Polygon |
Definition at line 86 of file mvsim_node_core.h.
using Msg_PoseArray = geometry_msgs::msg::PoseArray |
Definition at line 87 of file mvsim_node_core.h.
using Msg_PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped |
Definition at line 88 of file mvsim_node_core.h.
using Msg_TFMessage = tf2_msgs::msg::TFMessage |
Definition at line 95 of file mvsim_node_core.h.
using Msg_Twist = geometry_msgs::msg::Twist |
Definition at line 89 of file mvsim_node_core.h.
using Msg_Twist_CSPtr = geometry_msgs::msg::Twist::ConstSharedPtr |
Definition at line 90 of file mvsim_node_core.h.
using ros_Duration = rclcpp::Duration |
Definition at line 84 of file mvsim_node_core.h.
using ros_Time = rclcpp::Time |
Definition at line 83 of file mvsim_node_core.h.