1#ifndef PACSIMROS2HELPERS_HPP
2#define PACSIMROS2HELPERS_HPP
4#include "rclcpp/rclcpp.hpp"
6#include "geometry_msgs/msg/transform_stamped.hpp"
7#include "geometry_msgs/msg/twist_with_covariance_stamped.hpp"
8#include "pacsim/msg/gnss.hpp"
9#include "pacsim/msg/perception_detections.hpp"
10#include "sensor_msgs/msg/imu.hpp"
11#include "sensor_msgs/msg/joint_state.hpp"
13#include "visualization_msgs/msg/marker_array.hpp"
16#include <tf2/LinearMath/Quaternion.h>
23 visualization_msgs::msg::MarkerArray
markerFromLMs(
Track& in, std::string frame,
double time);
25 visualization_msgs::msg::MarkerArray
deleteAllMsg(std::string frame);
34 const LandmarkList& sensorLms, std::string frameId,
double time);
39 const Eigen::Vector3d& vel,
const Eigen::Vector3d& rot,
const std::string& frame,
double time);
41geometry_msgs::msg::TransformStamped
createRosTransformMsg(
const Eigen::Vector3d& trans,
const Eigen::Vector3d& rot,
42 const std::string& frame,
const std::string& child_frame,
double time);
45 const std::string& frame,
const std::string& child_frame,
double time);
48 const std::vector<std::string>& joint_names,
const std::vector<double>& joint_vals,
double time);
visualization_msgs::msg::MarkerArray markerFromLMs(Track &in, std::string frame, double time)
visualization_msgs::msg::MarkerArray deleteAllMsg(std::string frame)
geometry_msgs::msg::TransformStamped createStaticTransform(const std::string &frame, const std::string &child_frame, double time)
geometry_msgs::msg::TwistWithCovarianceStamped createRosTwistMsg(const Eigen::Vector3d &vel, const Eigen::Vector3d &rot, const std::string &frame, double time)
pacsim::msg::PerceptionDetections LandmarkListToRosMessage(const LandmarkList &sensorLms, std::string frameId, double time)
sensor_msgs::msg::Imu createRosImuMsg(const ImuData &data)
sensor_msgs::msg::JointState createRosJointMsg(const std::vector< std::string > &joint_names, const std::vector< double > &joint_vals, double time)
geometry_msgs::msg::TransformStamped createRosTransformMsg(const Eigen::Vector3d &trans, const Eigen::Vector3d &rot, const std::string &frame, const std::string &child_frame, double time)
pacsim::msg::GNSS createRosGnssMessage(const GnssData &data)