Utilities for particle cloud I/O over ROS interfaces. More...
#include <cmath>#include <map>#include <memory>#include <type_traits>#include <range/v3/range/primitives.hpp>#include <range/v3/view/take_exactly.hpp>#include <sophus/se2.hpp>#include <sophus/se3.hpp>#include <sophus/types.hpp>#include <beluga/algorithm/spatial_hash.hpp>#include <beluga/primitives.hpp>#include <beluga/views/sample.hpp>#include <beluga/views/zip.hpp>#include <beluga_ros/messages.hpp>#include <beluga_ros/tf2_eigen.hpp>#include <beluga_ros/tf2_sophus.hpp>

Go to the source code of this file.
Classes | |
| struct | beluga_ros::detail::almost_equal_to< T > |
| std::equal_to equivalent for near equality operations. More... | |
| struct | beluga_ros::detail::almost_equal_to< Sophus::SE2< Scalar > > |
| std::equal_to equivalent specialized for SE(2) types, with user resolutions. More... | |
Namespaces | |
| beluga_ros | |
| The main Beluga ROS namespace. | |
| beluga_ros::detail | |
Functions | |
| beluga_ros::msg::ColorRGBA | beluga_ros::detail::alphaHueToRGBA (float hue, float alpha) |
| Make an RGBA color based on hue alone. More... | |
| template<class Particles , class Particle = ranges::range_value_t<Particles>, class State = typename beluga::state_t<Particle>, class Scalar = typename State::Scalar> | |
| beluga_ros::msg::MarkerArray & | beluga_ros::assign_particle_cloud (Particles &&particles, beluga_ros::msg::MarkerArray &message) |
| Assign a pose distribution to a markers message for visualization with suitable resolutions. More... | |
| template<class Particles , class Message > | |
| Message & | beluga_ros::assign_particle_cloud (Particles &&particles, Message &message) |
| Assign a distribution to a particle cloud message. More... | |
| template<class Particles , class Particle = ranges::range_value_t<Particles>, class State = typename beluga::state_t<Particle>, class Weight = typename beluga::weight_t<Particle>, class Scalar = typename State::Scalar, typename = std::enable_if_t<std::is_same_v<State, typename Sophus::SE2<Scalar>>>> | |
| beluga_ros::msg::MarkerArray & | beluga_ros::assign_particle_cloud (Particles &&particles, Scalar linear_resolution, Scalar angular_resolution, beluga_ros::msg::MarkerArray &message) |
| Assign a pose distribution to a markers message for visualization. More... | |
| template<class Particles , class Particle = ranges::range_value_t<Particles>, class State = typename beluga::state_t<Particle>, class Scalar = typename State::Scalar, typename = std::enable_if_t< std::is_same_v<State, typename Sophus::SE2<Scalar>> || std::is_same_v<State, typename Sophus::SE3<Scalar>>>> | |
| beluga_ros::msg::PoseArray & | beluga_ros::assign_particle_cloud (Particles &&particles, std::size_t size, beluga_ros::msg::PoseArray &message) |
| Assign a pose distribution to a particle cloud message. More... | |
Utilities for particle cloud I/O over ROS interfaces.
Definition in file particle_cloud.hpp.