Program Listing for File beacon.hpp

Return to documentation for file (include/mrpt_msgs_bridge/beacon.hpp)

/* +------------------------------------------------------------------------+
   |                             mrpt_navigation                            |
   |                                                                        |
   | Copyright (c) 2014-2024, Individual contributors, see commit authors   |
   | See: https://github.com/mrpt-ros-pkg/mrpt_navigation                   |
   | All rights reserved. Released under BSD 3-Clause license. See LICENSE  |
   +------------------------------------------------------------------------+ */

#pragma once
#include <mrpt/obs/CObservationBeaconRanges.h>
#include <mrpt/poses/CPose3D.h>

#include <cstdint>
#include <geometry_msgs/msg/pose.hpp>
#include <mrpt_msgs/msg/observation_range_beacon.hpp>
#include <string>

namespace mrpt_msgs_bridge
{
bool fromROS(
    const mrpt_msgs::msg::ObservationRangeBeacon _msg,
    const mrpt::poses::CPose3D& _pose,
    mrpt::obs::CObservationBeaconRanges& _obj);

bool toROS(
    const mrpt::obs::CObservationBeaconRanges& _obj,
    mrpt_msgs::msg::ObservationRangeBeacon& _msg);

bool toROS(
    const mrpt::obs::CObservationBeaconRanges& _obj,
    mrpt_msgs::msg::ObservationRangeBeacon& _msg,
    geometry_msgs::msg::Pose& _pose);

}  // namespace mrpt_msgs_bridge