Class RosMsgsDatagramConverter

Class Documentation

class RosMsgsDatagramConverter

Class with static function to convert ros messages to locator’s datagrams.

Public Static Functions

static size_t convertClientControlMode2Message(const std::vector<char> &datagram, const rclcpp::Time &stamp, bosch_locator_bridge::msg::ClientControlMode &client_control_mode)

convertClientControlMode2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • stamp – ROS timestamp to assign to the message [INPUT]

  • client_control_mode – Describes the state of the localization client [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertMapDatagram2Message(const std::vector<char> &datagram, const rclcpp::Time &stamp, sensor_msgs::msg::PointCloud2 &out_pointcloud)

convertMapDatagram2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • stamp – ROS timestamp to assign to the message [INPUT]

  • out_pointcloud – Resulting converted map as point cloud [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertClientGlobalAlignVisualizationDatagram2Message(const std::vector<char> &datagram, bosch_locator_bridge::msg::ClientGlobalAlignVisualization &client_global_align_visualization, geometry_msgs::msg::PoseArray &poses, geometry_msgs::msg::PoseArray &landmark_poses)

convertClientGlobalAlignVisualizationDatagram2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • client_global_align_visualization – ClientGlobalAlignVisualization message [OUTPUT]

  • poses – A set of poses previously visited by the platform. The platform may have observed landmarks from some of these poses [OUTPUT]

  • landmark_poses – The array of poses according to the landmarks [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertClientLocalizationPoseDatagram2Message(const std::vector<char> &datagram, bosch_locator_bridge::msg::ClientLocalizationPose &client_localization_pose, geometry_msgs::msg::PoseStamped &pose, double covariance[6], geometry_msgs::msg::PoseStamped &lidar_odo_pose)

convertClientLocalizationPoseDatagram2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • client_localization_pose – ClientLocalizationPose message [OUTPUT]

  • pose – Pose message [OUTPUT]

  • lidar_odo_pose – Pose message in odom frame [OUTPUT]

  • covariance – array of 6 elements represents a 3x3 right triangular matrix [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertClientLocalizationVisualizationDatagram2Message(const std::vector<char> &datagram, bosch_locator_bridge::msg::ClientLocalizationVisualization &client_localization_visualization, geometry_msgs::msg::PoseStamped &pose, sensor_msgs::msg::PointCloud2 &scan)

convertClientLocalizationVisualizationDatagram2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • client_localization_visualization – ClientLocalizationVisualization message [OUTPUT]

  • pose – Pose message [OUTPUT]

  • scan – Scan message [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertClientMapVisualizationDatagram2Message(const std::vector<char> &datagram, bosch_locator_bridge::msg::ClientMapVisualization &client_map_visualization, geometry_msgs::msg::PoseStamped &pose, sensor_msgs::msg::PointCloud2 &scan, geometry_msgs::msg::PoseArray &path_poses)

convertClientMapVisualizationDatagram2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • client_map_visualization – ClientMapVisualization message [OUTPUT]

  • pose – Pose message [OUTPUT]

  • scan – Scan message [OUTPUT]

  • path_poses – PathPoses message [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertClientRecordingVisualizationDatagram2Message(const std::vector<char> &datagram, bosch_locator_bridge::msg::ClientRecordingVisualization &client_recording_visualization, geometry_msgs::msg::PoseStamped &pose, sensor_msgs::msg::PointCloud2 &scan, geometry_msgs::msg::PoseArray &path_poses)

convertClientRecordingVisualizationDatagram2Message

Parameters:
  • datagram – The binary data input datagram [INPUT]

  • client_recording_visualization – ClientRecordingVisualization message [OUTPUT]

  • pose – Pose message [OUTPUT]

  • scan – Scan message [OUTPUT]

  • path_poses – PathPoses message [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertPose2DDoubleDatagram2Message(Poco::BinaryReader &binary_reader, geometry_msgs::msg::Pose &pose)

convertPose2DDoubleDatagram2Message Takes a binary_reader with a DOUBLE precision pose datagram coming next and converts to a geometry_msgs::msg::Pose

Parameters:
  • binary_reader – The binary_reader pointing to a DOUBLE precision pose datagram

  • pose – Converted pose [OUTPUT]

Returns:

number of bytes parsed successfully

static size_t convertPose2DSingleDatagram2Message(Poco::BinaryReader &binary_reader, geometry_msgs::msg::Pose &pose)

convertPose2DSingleDatagram2Message Takes a binary_reader with a SINGLE precision pose datagram coming next and converts to a geometry_msgs::msg::Pose

Parameters:
  • binary_reader – The binary_reader pointing to a SINGLE precision pose datagram

  • pose – Converted pose [OUTPUT]

Returns:

number of bytes parsed successfully

static Poco::Buffer<char> convertLaserScan2DataGram(const sensor_msgs::msg::LaserScan::SharedPtr msg, size_t scan_num, rclcpp::Node::SharedPtr node)

convertLaserScan2DataGram Converts a sensor_msgs::msg::LaserScan message from ros and converts it to the datagram structure required for the binary interface of the locator.

Parameters:

msg – The laser scan message @oaram scan_num The current scan number

Returns:

The data shaped into the datagram structure required by the locator

static Poco::Buffer<char> convertOdometry2DataGram(const nav_msgs::msg::Odometry::SharedPtr msg, size_t odom_num, rclcpp::Node::SharedPtr node)

convertOdometry2DataGram Converts a nav_msgs::msg::Odometry message from ros and converts it to the datagram structure required for the binary interface of the locator.

Parameters:

msg – The odometry message @oaram odom_num The current odomerty observation number

Returns:

The data shaped into the datagram structure required by the locator

static Poco::JSON::Object makePose2d(const geometry_msgs::msg::Pose2D &pose)