Class SimulationServer¶
- Defined in File simulation_server.h
Class Documentation¶
-
class
SimulationServer¶ Public Functions
-
SimulationServer(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private)¶
-
SimulationServer(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private, const EsdfMap::Config &esdf_config, const EsdfIntegrator::Config &esdf_integrator_config, const TsdfMap::Config &tsdf_config, const TsdfIntegratorBase::Config &tsdf_integrator_config)¶
-
virtual
~SimulationServer()¶
-
void
run()¶ Runs all of the below functions in the correct order:
-
virtual void
prepareWorld() = 0¶ Creates a new world, and prepares ground truth SDF(s).
-
void
generateSDF()¶ Generates a SDF by generating random poses and putting them into an SDF.
-
void
evaluate()¶ Evaluate errors…
-
void
visualize()¶ Visualize results. :)
Protected Functions
-
void
getServerConfigFromRosParam(const ros::NodeHandle &nh_private)¶
-
bool
generatePlausibleViewpoint(FloatingPoint min_distance, Point *ray_origin, Point *ray_direction) const¶ Convenience function to generate valid viewpoints.
Protected Attributes
-
ros::NodeHandle
nh_¶
-
ros::NodeHandle
nh_private_¶
-
ros::Publisher
sim_pub_¶
-
ros::Publisher
tsdf_gt_pub_¶
-
ros::Publisher
esdf_gt_pub_¶
-
ros::Publisher
tsdf_gt_mesh_pub_¶
-
ros::Publisher
tsdf_test_pub_¶
-
ros::Publisher
esdf_test_pub_¶
-
ros::Publisher
tsdf_test_mesh_pub_¶
-
ros::Publisher
view_ptcloud_pub_¶
-
FloatingPoint
voxel_size_¶
-
int
voxels_per_side_¶
-
std::string
world_frame_¶
-
bool
generate_occupancy_¶
-
bool
visualize_¶
-
FloatingPoint
visualization_slice_level_¶
-
bool
generate_mesh_¶
-
bool
incremental_¶
-
bool
add_robot_pose_¶
-
FloatingPoint
truncation_distance_¶
-
FloatingPoint
esdf_max_distance_¶
-
size_t
max_attempts_to_generate_viewpoint_¶
-
Eigen::Vector2i
depth_camera_resolution_¶
-
FloatingPoint
fov_h_rad_¶
-
FloatingPoint
max_dist_¶
-
FloatingPoint
min_dist_¶
-
int
num_viewpoints_¶
-
SimulationWorld
world_¶
-
std::unique_ptr<Layer<OccupancyVoxel>>
occ_test_¶
-
std::unique_ptr<TsdfIntegratorBase>
tsdf_integrator_¶
-
std::unique_ptr<EsdfIntegrator>
esdf_integrator_¶
-
std::unique_ptr<OccupancyIntegrator>
occ_integrator_¶
-
std::unique_ptr<EsdfOccIntegrator>
esdf_occ_integrator_¶
-