beluga_ros Namespace Reference

beluga_ros Namespace Reference#

Beluga ROS: beluga_ros Namespace Reference
Beluga ROS
beluga_ros Namespace Reference

The main Beluga ROS namespace. More...

Classes

struct  AmclParams
 Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation. More...
 
class  Amcl
 
class  LaserScan
 Thin wrapper type for 2D sensor_msgs/LaserScan messages. More...
 
class  OccupancyGrid
 Thin wrapper type for 2D nav_msgs/OccupancyGrid messages. More...
 
class  PointCloud3
 Thin wrapper type for 3D sensor_msgs/PointCloud2 messages with dense layouts. More...
 
class  SparsePointCloud3
 Thin wrapper for 3D sensor_msgs/PointCloud2 messages with potentially sparse layouts. More...
 

Typedefs

using PointCloud3d = PointCloud3< double, false >
 Non-strict alias for PointCloud3 of double type.
 
using PointCloud3f = PointCloud3< float, false >
 Non-strict alias for PointCloud3 of float type.
 
using SparsePointCloud3d = SparsePointCloud3< double, false >
 Non-strict alias for SparsePointCloud3 of double type.
 
using SparsePointCloud3f = SparsePointCloud3< float, false >
 Non-strict alias for SparsePointCloud3 of float type.
 

Functions

template<typename T >
void assign_likelihood_field (const beluga::ValueGrid2< T > &likelihood_field, const Sophus::SE2d &origin, nav_msgs::msg::OccupancyGrid &message)
 Convert from likelihood data to ROS2 message.
 
template<class Message >
Message & stamp_message (std::string_view frame_id, rclcpp::Time timestamp, Message &message)
 Stamp a message with a frame ID and timestamp. More...
 
visualization_msgs::msg::MarkerArray & stamp_message (std::string_view frame_id, rclcpp::Time timestamp, visualization_msgs::msg::MarkerArray &message)
 Stamp all markers in a marker array message with a frame ID and timestamp. More...
 
template<typename MapType , int NDim>
std::pair< visualization_msgs::msg::MarkerArray, bool > assign_obstacle_map (const beluga::SparseValueGrid< MapType, NDim > &grid, visualization_msgs::msg::MarkerArray &message)
 
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>>>>
geometry_msgs::msg::PoseArray & assign_particle_cloud (Particles &&particles, std::size_t size, geometry_msgs::msg::PoseArray &message)
 Assign a pose distribution to a particle cloud message. 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>> || std::is_same_v<State, typename Sophus::SE3<Scalar>>>>
visualization_msgs::msg::MarkerArray & assign_particle_cloud (Particles &&particles, Scalar linear_resolution, Scalar angular_resolution, visualization_msgs::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>
visualization_msgs::msg::MarkerArray & assign_particle_cloud (Particles &&particles, visualization_msgs::msg::MarkerArray &message)
 Assign a pose distribution to a markers message for visualization with suitable resolutions. More...
 

Detailed Description

The main Beluga ROS namespace.

Function Documentation

◆ assign_obstacle_map()

template<typename MapType , int NDim>
std::pair<visualization_msgs::msg::MarkerArray, bool> beluga_ros::assign_obstacle_map ( const beluga::SparseValueGrid< MapType, NDim > &  grid,
visualization_msgs::msg::MarkerArray &  message 
)

Assign an ellipsoid to each cell of a SparseValueGrid. A cube is used instead if the distribution of the cell is not suitable for the rotation matrix creation.

Parameters
gridA SparseValueGrid that contains cells representing obstacles.
[out]messageA MarkerArray that will contain the shapes
Returns
A std::pair with the MarkerArray containing the shapes and a boolean indicating if at least one cube was generated.
Template Parameters
MapTypeContainer that maps from Eigen::Vector<int, NDim> to the type of the cell. See SparseValueGrid.
NDimDimension of the grid.

◆ assign_particle_cloud() [1/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.

◆ assign_particle_cloud() [2/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>> || std::is_same_v<State, typename Sophus::SE3<Scalar>>>>
visualization_msgs::msg::MarkerArray& beluga_ros::assign_particle_cloud ( Particles &&  particles,
Scalar  linear_resolution,
Scalar  angular_resolution,
visualization_msgs::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.

◆ assign_particle_cloud() [3/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>>>>
geometry_msgs::msg::PoseArray& beluga_ros::assign_particle_cloud ( Particles &&  particles,
std::size_t  size,
geometry_msgs::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.

◆ 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>
visualization_msgs::msg::MarkerArray& beluga_ros::assign_particle_cloud ( Particles &&  particles,
visualization_msgs::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.

◆ stamp_message() [1/2]

template<class Message >
Message& beluga_ros::stamp_message ( std::string_view  frame_id,
rclcpp::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.

◆ stamp_message() [2/2]

visualization_msgs::msg::MarkerArray& beluga_ros::stamp_message ( std::string_view  frame_id,
rclcpp::Time  timestamp,
visualization_msgs::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.