Skip to content

Commit

Permalink
Limiting the scope of variables moveit#874
Browse files Browse the repository at this point in the history
Limited the scope of variables in moveit_core/collision_detection
  • Loading branch information
SalahSoliman authored and Shobuj-Paul committed Sep 5, 2023
1 parent 84421ea commit 72aac61
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 7 deletions.
1 change: 0 additions & 1 deletion moveit_core/collision_detection/src/collision_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ namespace collision_detection
{
void CollisionResult::print() const
{
rclcpp::Clock clock;
if (!contacts.empty())
{
#pragma GCC diagnostic push
Expand Down
11 changes: 5 additions & 6 deletions moveit_core/collision_detection/src/collision_octomap_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,13 +98,13 @@ int collision_detection::refineContactNormals(const World::ObjectConstPtr& objec
continue;
}

double cell_size = 0;
if (!object->shapes_.empty())
{
const shapes::ShapeConstPtr& shape = object->shapes_[0];
const std::shared_ptr<const shapes::OcTree> shape_octree = std::dynamic_pointer_cast<const shapes::OcTree>(shape);
if (shape_octree)
{
double cell_size = 0;
std::shared_ptr<const octomap::OcTree> octree = shape_octree->octree;
cell_size = octree->getResolution();
for (auto& contact_info : contact_vector)
Expand Down Expand Up @@ -174,7 +174,6 @@ bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const doub
const double& r_multiple, const octomath::Vector3& contact_point,
octomath::Vector3& normal, double& depth, const bool estimate_depth)
{
double intensity;
if (estimate_depth)
{
octomath::Vector3 surface_point;
Expand All @@ -191,6 +190,7 @@ bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const doub
else // just get normals, no depth
{
octomath::Vector3 gradient;
double intensity;
if (sampleCloud(cloud, spacing, r_multiple, contact_point, intensity, gradient))
{
normal = gradient.normalized();
Expand All @@ -211,18 +211,17 @@ bool findSurface(const octomap::point3d_list& cloud, const double& spacing, cons
const double& r_multiple, const octomath::Vector3& seed, octomath::Vector3& surface_point,
octomath::Vector3& normal)
{
const double epsilon = 1e-10;
const int iterations = 10;
double intensity = 0;

octomath::Vector3 p = seed, dp, gs;
const int iterations = 10;
for (int i = 0; i < iterations; ++i)
{
double intensity = 0;
if (!sampleCloud(cloud, spacing, r_multiple, p, intensity, gs))
return false;
const double s = iso_value - intensity;
dp = (gs * -s) * (1.0 / std::max(gs.dot(gs), epsilon));
p = p + dp;
const double epsilon = 1e-10;
if (dp.dot(dp) < epsilon)
{
surface_point = p;
Expand Down

0 comments on commit 72aac61

Please sign in to comment.