#include <raycaster.hpp>
|
| Raycaster () |
|
| Raycaster (std::string embree_config) |
|
| ~Raycaster () |
|
template<typename T , typename... Ts> |
void | addPrimitive (std::string name, Ts &&... xs) |
|
const sensor_msgs::msg::PointCloud2 | raycast (const std::string &frame_id, const rclcpp::Time &stamp, const geometry_msgs::msg::Pose &origin, double max_distance=300, double min_distance=0) |
|
const std::vector< std::string > & | getDetectedObject () const |
|
void | setDirection (const simulation_api_schema::LidarConfiguration &configuration, double horizontal_angle_start=0, double horizontal_angle_end=2 *M_PI) |
|
◆ Raycaster() [1/2]
simple_sensor_simulator::Raycaster::Raycaster |
( |
| ) |
|
◆ Raycaster() [2/2]
simple_sensor_simulator::Raycaster::Raycaster |
( |
std::string |
embree_config | ) |
|
|
explicit |
◆ ~Raycaster()
simple_sensor_simulator::Raycaster::~Raycaster |
( |
| ) |
|
◆ addPrimitive()
template<typename T , typename... Ts>
void simple_sensor_simulator::Raycaster::addPrimitive |
( |
std::string |
name, |
|
|
Ts &&... |
xs |
|
) |
| |
|
inline |
◆ getDetectedObject()
const std::vector< std::string > & simple_sensor_simulator::Raycaster::getDetectedObject |
( |
| ) |
const |
◆ raycast()
const sensor_msgs::msg::PointCloud2 simple_sensor_simulator::Raycaster::raycast |
( |
const std::string & |
frame_id, |
|
|
const rclcpp::Time & |
stamp, |
|
|
const geometry_msgs::msg::Pose & |
origin, |
|
|
double |
max_distance = 300 , |
|
|
double |
min_distance = 0 |
|
) |
| |
◆ setDirection()
void simple_sensor_simulator::Raycaster::setDirection |
( |
const simulation_api_schema::LidarConfiguration & |
configuration, |
|
|
double |
horizontal_angle_start = 0 , |
|
|
double |
horizontal_angle_end = 2 * M_PI |
|
) |
| |
The documentation for this class was generated from the following files:
- simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/lidar/raycaster.hpp
- simulation/simple_sensor_simulator/src/sensor_simulation/lidar/raycaster.cpp