|
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 & | 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 & | 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 & | 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 & | assign_particle_cloud (Particles &&particles, std::size_t size, beluga_ros::msg::PoseArray &message) |
| Assign a pose distribution to a particle cloud message. More...
|
|
beluga_ros::msg::MarkerArray & | stamp_message (std::string_view frame_id, detail::Time timestamp, beluga_ros::msg::MarkerArray &message) |
| Stamp all markers in a marker array message with a frame ID and timestamp. More...
|
|
template<class Message > |
Message & | stamp_message (std::string_view frame_id, detail::Time timestamp, Message &message) |
| Stamp a message with a frame ID and timestamp. More...
|
|
The main Beluga ROS namespace.
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.
- Parameters
-
| particles | Pose distribution, as a particle cloud itself. |
[out] | message | Markers message to be assigned. |
- Template Parameters
-
Particles | A sized range type whose value type satisfies Particle named requirements. |
Definition at line 274 of file particle_cloud.hpp.
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.
- Parameters
-
| particles | Pose distribution, as a particle cloud itself. |
| linear_resolution | Linear resolution, in meters, for visualization. |
| angular_resolution | Angular resolution, in radians, for visualization. |
[out] | message | Markers message to be assigned. |
- Template Parameters
-
Particles | A sized range type whose value type satisfies Particle named requirements. |
Definition at line 153 of file particle_cloud.hpp.
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. |
[out] | message | Particle cloud message to be assigned. |
- Template Parameters
-
Particles | A sized range type whose value type satisfies Particle named requirements. |
Definition at line 111 of file particle_cloud.hpp.