Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
DCO 1.1 Signed-off-by: Tatsuya Ishihara <[email protected]>
  • Loading branch information
tatsuya-ishihara committed Nov 18, 2024
1 parent 33ab115 commit 6f7f65c
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class GridMapGroundFilterNode : public AbstractGroundFilterNode
float ground_confidence_interpolate_decay_;

static const int livox_num_points_;
static const float lixox_tan_fov_angle_;
static const float livox_tan_fov_angle_;

std::vector<int64_t> grid_half_patch_sizes_;
float log_odds_prior_;
Expand Down
4 changes: 2 additions & 2 deletions cabot_navigation2/src/grid_map_ground_filter_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ namespace cabot_navigation2

// https://www.livoxtech.com/mid-70/specs
const int GridMapGroundFilterNode::livox_num_points_ = 100000;
const float GridMapGroundFilterNode::lixox_tan_fov_angle_ = std::tan(M_PI * (70.4 / 2.0) / 180.0);
const float GridMapGroundFilterNode::livox_tan_fov_angle_ = std::tan(M_PI * (70.4 / 2.0) / 180.0);

GridMapGroundFilterNode::GridMapGroundFilterNode(const rclcpp::NodeOptions & options)
: AbstractGroundFilterNode("grid_map_ground_filter_node", options),
Expand Down Expand Up @@ -163,7 +163,7 @@ void GridMapGroundFilterNode::odomCallback(const nav_msgs::msg::Odometry::Shared

int GridMapGroundFilterNode::calcLivoxGridEstimatedNumPoints(float distance, float resolution)
{
const float fov_radius = distance * lixox_tan_fov_angle_;
const float fov_radius = distance * livox_tan_fov_angle_;
const float fov_area = M_PI * std::pow(fov_radius, 2.0);
return livox_num_points_ * std::pow(resolution, 2.0) / fov_area;
}
Expand Down

0 comments on commit 6f7f65c

Please sign in to comment.