Template Function beluga_ros::assign_particle_cloud(Particles&&, std::size_t, beluga_ros::msg::PoseArray&)
Defined in File particle_cloud.hpp
Function Documentation
-
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.
- Parameters:
particles – Pose distribution, as a particle cloud itself.
size – Sample size of the particle cloud.
message – [out] Particle cloud message to be assigned.
- Template Parameters:
Particles – A sized range type whose value type satisfies Particle named requirements.