Namespaces | Classes | Functions | Variables
beluga_ros Namespace Reference

The main Beluga ROS namespace. More...

Namespaces

 conversion_utils
 
 detail
 
 msg
 Compatibility layer for ROS 1 and ROS 2 messages.
 
 occupancy_grid_to_ndt
 

Classes

class  Amcl
 
struct  AmclParams
 Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation. More...
 
class  LaserScan
 Thin wrapper type for 2D sensor_msgs/LaserScan messages. More...
 
class  OccupancyGrid
 Thin wrapper type for 2D nav_msgs/OccupancyGrid messages. More...
 

Functions

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...
 

Variables

list __all__ = ['occupancy_grid_to_ndt', 'conversion_utils']
 

Detailed Description

The main Beluga ROS namespace.

Function Documentation

◆ assign_particle_cloud() [1/4]

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
particlesPose distribution, as a particle cloud itself.
[out]messageMarkers message to be assigned.
Template Parameters
ParticlesA sized range type whose value type satisfies Particle named requirements.

Definition at line 274 of file particle_cloud.hpp.

◆ assign_particle_cloud() [2/4]

template<class Particles , class Message >
Message& beluga_ros::assign_particle_cloud ( Particles &&  particles,
Message &  message 
)

Assign a distribution to a particle cloud message.

Particle cloud sample size will match that of the given distribution.

Parameters
particlesDistribution to sample, as a particle cloud itself.
[out]messageParticle cloud message to be assigned.
Template Parameters
ParticlesA sized range type whose value type satisfies Particle named requirements.

Definition at line 133 of file particle_cloud.hpp.

◆ assign_particle_cloud() [3/4]

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
particlesPose distribution, as a particle cloud itself.
linear_resolutionLinear resolution, in meters, for visualization.
angular_resolutionAngular resolution, in radians, for visualization.
[out]messageMarkers message to be assigned.
Template Parameters
ParticlesA sized range type whose value type satisfies Particle named requirements.

Definition at line 153 of file particle_cloud.hpp.

◆ assign_particle_cloud() [4/4]

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
particlesPose distribution, as a particle cloud itself.
sizeSample size of the particle cloud.
[out]messageParticle cloud message to be assigned.
Template Parameters
ParticlesA sized range type whose value type satisfies Particle named requirements.

Definition at line 111 of file particle_cloud.hpp.

◆ stamp_message() [1/2]

beluga_ros::msg::MarkerArray& beluga_ros::stamp_message ( std::string_view  frame_id,
detail::Time  timestamp,
beluga_ros::msg::MarkerArray &  message 
)
inline

Stamp all markers in a marker array message with a frame ID and timestamp.

Parameters
frame_idFrame ID to stamp markers with.
timestampTime to stamp markers at.
[out]messageMessage to be stamped.

Definition at line 122 of file messages.hpp.

◆ stamp_message() [2/2]

template<class Message >
Message& beluga_ros::stamp_message ( std::string_view  frame_id,
detail::Time  timestamp,
Message &  message 
)

Stamp a message with a frame ID and timestamp.

Parameters
frame_idFrame ID to stamp the message with.
timestampTime to stamp the message at.
[out]messageMessage to be stamped.
Template Parameters
MessageA message type with a header.

Definition at line 109 of file messages.hpp.

Variable Documentation

◆ __all__

list beluga_ros.__all__ = ['occupancy_grid_to_ndt', 'conversion_utils']
private

Definition at line 17 of file __init__.py.



beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02