Skip to content

Commit

Permalink
chore: tidy up
Browse files Browse the repository at this point in the history
  • Loading branch information
mebasoglu committed Apr 1, 2024
1 parent 07daffc commit a2cf149
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 7 deletions.
10 changes: 7 additions & 3 deletions nebula_common/include/nebula_common/velodyne/velodyne_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,10 @@ namespace nebula
namespace drivers
{

/// @brief Invalid region on the cloud to be removed
struct InvalidRegion {
/// @brief Invalid region on the cloud to be removed. `start` and `end` represent angles of the
/// region.
struct InvalidRegion
{
uint16_t start;
uint16_t end;
};
Expand All @@ -27,7 +29,9 @@ struct VelodyneSensorConfiguration : LidarConfigurationBase
uint16_t cloud_min_angle;
uint16_t cloud_max_angle;
bool invalid_point_remove;
std::map<int, std::vector<InvalidRegion>> invalid_regions;
std::map<int, std::vector<InvalidRegion>>
invalid_regions; // Key holds the channel id, value holds invalid regions belong to that
// channel
};
/// @brief Convert VelodyneSensorConfiguration to string (Overloading the << operator)
/// @param os
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -183,8 +183,9 @@ class VelodyneScanDecoder
/// @brief Resetting overflowed point cloud buffer
virtual void reset_overflow(double time_stamp) = 0;

/// @brief Checks if the point is invalid.
/// @param point The point to check.
/// @brief Checks if the point is inside invalid regions.
/// @param channel Channel id of the point.
/// @param azimuth Azimuth angle of the point.
/// @return True if the point is invalid, false otherwise.
bool check_invalid_point(const int & channel, const uint16_t & azimuth)
{
Expand Down
4 changes: 2 additions & 2 deletions nebula_ros/launch/velodyne_launch_all_hw.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@

<arg name="setup_sensor" default="True" description="Enable sensor setup on hw-driver."/>

<arg name="invalid_point_remove" default="true"/>
<arg name="invalid_point_remove" default="false"/>
<arg name="invalid_regions"
default="'[[12, 31110, 31495], [0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600], [4, 3000, 4300], [5, 2950, 4050], [6, 3100, 3800], [0, 26000, 32200], [1, 26000, 32200], [2, 26000, 31000], [3, 26000, 30000], [4, 26000, 28000]]'"/>
default="'[[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]]'"/>

<node pkg="nebula_ros" exec="velodyne_driver_ros_wrapper_node"
name="velodyne_cloud" output="screen">
Expand Down

0 comments on commit a2cf149

Please sign in to comment.