Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enhancement/use hpp for headers #3113

Merged
merged 60 commits into from
Nov 29, 2024
Merged
Show file tree
Hide file tree
Changes from 53 commits
Commits
Show all changes
60 commits
Select commit Hold shift + click to select a range
2c5e59f
Replaces moveit imports from .h to .hpp
TSNoble Nov 17, 2024
fcc088c
Replaces moveit imports from .h to .hpp
TSNoble Nov 17, 2024
3d8f70a
Renames all .h files to .hpp
TSNoble Nov 17, 2024
252e5da
Fixes moveit_core compiler errors
TSNoble Nov 17, 2024
c4ebfc5
Fixes compilation up to moveit_planners
TSNoble Nov 17, 2024
f64a9fa
Fixes compilation up to moveit_py
TSNoble Nov 17, 2024
603ba86
Fixes compilation up to moveit_ros
TSNoble Nov 17, 2024
4340e08
Merge branch 'main' into enhancement/use-hpp-for-headers
TSNoble Nov 17, 2024
3199c85
Updates MIGRATION.md
TSNoble Nov 17, 2024
e5b505f
Merges with main
TSNoble Nov 17, 2024
fc0425d
Fixes chomp imports
TSNoble Nov 17, 2024
f0d1f21
Fixes ikfast imports
TSNoble Nov 17, 2024
294f890
Adds create_deprecated_headers.py
TSNoble Nov 17, 2024
be8f3fd
Fixes lingering version.h
TSNoble Nov 17, 2024
4ae41ea
Fixes python formatting
TSNoble Nov 17, 2024
5a2843c
Updates MIGRATION.md
TSNoble Nov 17, 2024
84a6ab0
Fixes MIGRATION.md formatting
TSNoble Nov 17, 2024
483f5b5
Fixes ikfast errors
TSNoble Nov 17, 2024
d0bb7e7
Fixes ikfast errors
TSNoble Nov 17, 2024
194d544
Fixes tf2_ros imports
TSNoble Nov 17, 2024
7924769
Fixes ikfast errors
TSNoble Nov 17, 2024
0d2080d
Rename ikfast.hpp to ikfast.h
TSNoble Nov 18, 2024
7eb5cc2
Applies changes from d529029062305520817c261be6601bab94b21255
TSNoble Nov 18, 2024
4028c13
Applies changes from d529029062305520817c261be6601bab94b21255
TSNoble Nov 18, 2024
6e6f300
Fixes typos
TSNoble Nov 18, 2024
3c0ad59
Reverts botched merge
TSNoble Nov 18, 2024
3fa7b06
Partially fixes merge conflicts
TSNoble Nov 18, 2024
4ef4ccd
Merge branch 'main' into enhancement/use-hpp-for-headers
TSNoble Nov 18, 2024
695d1c7
Fixes merge conflicts
TSNoble Nov 18, 2024
f9ff2c3
Merge branch 'main' into enhancement/use-hpp-for-headers
rr-tom-noble Nov 19, 2024
4564094
Adds CMake wrapper around python script
TSNoble Nov 19, 2024
03c5143
Adds create_deprecated_headers() call after every install() that uses…
TSNoble Nov 19, 2024
a59cd57
Fixes formatting
TSNoble Nov 19, 2024
bf11b68
Fixes script
TSNoble Nov 19, 2024
71efe77
Simplifies script
TSNoble Nov 19, 2024
939f24f
Removes create_deprecated_headers() macro calls
TSNoble Nov 21, 2024
cdd0b63
Adds authorship and TODOs
TSNoble Nov 21, 2024
bdf8e7b
Adds new header generator
TSNoble Nov 21, 2024
b0d563f
Removes test script
TSNoble Nov 21, 2024
a7465de
Updates deprecated headers script
TSNoble Nov 21, 2024
4b3304c
Adds #pragma once to files that don't have it
TSNoble Nov 21, 2024
16eeb75
Generate headers where we can
TSNoble Nov 21, 2024
bd16103
Applies formatting
TSNoble Nov 21, 2024
b4a6299
Deletes referenced to now removed cmake file
TSNoble Nov 21, 2024
aca9ab1
Minor tweaks to script and updates .h files
TSNoble Nov 21, 2024
3b0ad74
Temporarily disables deprecation msg to reduce compiler spam
TSNoble Nov 21, 2024
4d8bdf1
Fixes script comment
TSNoble Nov 21, 2024
f2dc4c8
Applies formatting
TSNoble Nov 21, 2024
c2b681f
Merge branch 'main' into enhancement/use-hpp-for-headers
TSNoble Nov 22, 2024
31f6d4e
Fixes autogen script
TSNoble Nov 22, 2024
9793f46
Delete moveit_core/macros/include/moveit/macros/deprecation.hpp
TSNoble Nov 23, 2024
94032aa
Delete moveit_core/macros/include/moveit/macros/deprecation.h
TSNoble Nov 23, 2024
d8ed584
Merge branch 'main' into enhancement/use-hpp-for-headers
TSNoble Nov 23, 2024
23b3882
Update moveit/scripts/create_deprecated_headers.py
rr-tom-noble Nov 26, 2024
e25d46a
Update moveit/scripts/create_deprecated_headers.py
rr-tom-noble Nov 26, 2024
dda37c4
Updates script copyright
rr-tom-noble Nov 26, 2024
4e3667b
Refactors script. Removes newline from parameter_name_list.hpp
TSNoble Nov 26, 2024
a10a31a
Removes now unused parse_args() function
TSNoble Nov 26, 2024
04f375f
Updates .h disclaimer with more info. Regenerates headers.
TSNoble Nov 28, 2024
cc3981a
Merge branch 'main' into enhancement/use-hpp-for-headers
sea-bass Nov 29, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
The table of contents is too big for display.
Diff view
Diff view
  •  
  •  
  •  
1 change: 1 addition & 0 deletions MIGRATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
API changes in MoveIt releases

## ROS Rolling
- [11/2024] All MoveIt 2 headers have been updated to use the .hpp extension. .h headers are now autogenerated with a deprecation warning, and may be removed in future releases. Please update your imports to use the .hpp headers.
- [11/2024] Added flags to control padding to CollisionRequest. This change deprecates PlanningScene::checkCollisionUnpadded(..) functions. Please use PlanningScene::checkCollision(..) with a req.pad_environment_collisions = false;

- [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse.
Expand Down
129 changes: 129 additions & 0 deletions moveit/scripts/create_deprecated_headers.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
#!/usr/bin/env python3
# -*- coding: utf-8 -*-

# Copyright 2021 PickNik Inc.
TSNoble marked this conversation as resolved.
Show resolved Hide resolved
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
#
# * Neither the name of the PickNik Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

# Author: Tom Noble

import sys
import logging
from typing import List, Tuple
from pathlib import Path


class NoIncludeGuard(Exception):
ERROR = "No include guard found in {}.hpp. Unable to generate pretext."

def __init__(self, file: Path):
super().__init__(self.ERROR.format(file))


class NoIncludeDirectory(Exception):
ERROR = "No includue directory found for {}.hpp. Unable to generate relative .hpp include"
rr-tom-noble marked this conversation as resolved.
Show resolved Hide resolved

def __init__(self, file: Path):
super().__init__(self.ERROR.format(file))


class HppFile:
def __init__(self, path: Path):
self.path = path
self.guard = "#pragma once"
self.pretext = self.pretext()
self.include = self.include()

def drop_data_after(self, data: str, match: str):
return data[: data.find(match) + len(match)]

def read(self) -> str:
data = open(self.path, "r").read()
contains_guard = self.guard in data
if not contains_guard:
raise NoIncludeGuard(self.path)
return data

def pretext(self) -> str:
data = self.read()
return self.drop_data_after(data, self.guard)

def include(self) -> str:
ends_with_include = lambda p: str(p).endswith("include")
include_paths = [p for p in self.path.parents if ends_with_include(p)]
if not include_paths:
raise NoIncludeDirectory(self.path)
relative_import = self.path.relative_to(include_paths[0])
return f"#include <{relative_import}>"


class DeprecatedHeader:
def __init__(self, hpp: HppFile):
self.hpp = hpp
self.path = hpp.path.with_suffix(".h")
self.prefix = f"/* This file was autogenerated by {Path(__file__).name} */"
self.warn = '#pragma message(".h header is obsolete. Please use the .hpp")'
rr-tom-noble marked this conversation as resolved.
Show resolved Hide resolved
self.contents = self.contents()

def contents(self) -> str:
items = [self.prefix, self.hpp.pretext, self.warn, self.hpp.include]
return "\n\n".join(items)


def parse_args(args: List) -> bool:
n_args = len(sys.argv)
if n_args > 2:
sys.exit("Usage: ./create_deprecated_headers [--apply]")
apply = "--apply" == sys.argv[1] if n_args == 2 else False
return apply
TSNoble marked this conversation as resolved.
Show resolved Hide resolved


if __name__ == "__main__":
apply = parse_args(sys.argv)
hpp_paths = list(Path.cwd().rglob("*.hpp"))
print(f"Generating deprecated .h files for {len(hpp_paths)} .hpp files...")
processed = []
bad = []
TSNoble marked this conversation as resolved.
Show resolved Hide resolved
for hpp_path in hpp_paths:
try:
processed.append(HppFile(hpp_path))
except NoIncludeDirectory as e:
bad.append(str(hpp_path))
except NoIncludeGuard as e:
bad.append(str(hpp_path))
print(f"Summary: Can generate {len(processed)} .h files")
if bad:
print(f"Cannot generate .h files for the following files:")
print("\n".join(bad))
if apply and bad:
answer = input("Proceed to generate? (y/n): ")
apply = answer.lower() == "y"
if apply:
print(f"Proceeding to generate {len(processed)} .h files...")
to_generate = [DeprecatedHeader(hpp) for hpp in processed]
_ = [open(h.path, "w").write(h.contents) for h in to_generate]
print("Done. (You may need to rerun formatting)")
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
/* This file was autogenerated by create_deprecated_headers.py */

/*********************************************************************
* Software License Agreement (BSD License)
*
Expand Down Expand Up @@ -36,18 +38,6 @@

#pragma once

#include <moveit/collision_detection/collision_detector_allocator.h>
#include <moveit/collision_detection/allvalid/collision_env_allvalid.h>

#include <moveit_collision_detection_export.h>
#pragma message(".h header is obsolete. Please use the .hpp")

namespace collision_detection
{
/** \brief An allocator for AllValid collision detectors */
class MOVEIT_COLLISION_DETECTION_EXPORT CollisionDetectorAllocatorAllValid
: public CollisionDetectorAllocatorTemplate<CollisionEnvAllValid, CollisionDetectorAllocatorAllValid>
{
public:
static const std::string NAME; // defined in collision_env_allvalid.cpp
};
} // namespace collision_detection
#include <moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp>
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Acorn Pooley, Ioan Sucan */

#pragma once

#include <moveit/collision_detection/collision_detector_allocator.hpp>
#include <moveit/collision_detection/allvalid/collision_env_allvalid.hpp>

#include <moveit_collision_detection_export.h>

namespace collision_detection
{
/** \brief An allocator for AllValid collision detectors */
class MOVEIT_COLLISION_DETECTION_EXPORT CollisionDetectorAllocatorAllValid
: public CollisionDetectorAllocatorTemplate<CollisionEnvAllValid, CollisionDetectorAllocatorAllValid>
{
public:
static const std::string NAME; // defined in collision_env_allvalid.cpp
};
} // namespace collision_detection
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
/* This file was autogenerated by create_deprecated_headers.py */

/*********************************************************************
* Software License Agreement (BSD License)
*
Expand Down Expand Up @@ -36,41 +38,6 @@

#pragma once

#include <moveit/collision_detection/collision_env.h>

namespace collision_detection
{
/** \brief Collision environment which always just returns no collisions.
*
* This can be used to save resources if collision checking is not important. */
class CollisionEnvAllValid : public CollisionEnv
{
public:
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model, double padding = 0.0, double scale = 1.0);
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world, double padding = 0.0,
double scale = 1.0);
CollisionEnvAllValid(const CollisionEnv& other, const WorldPtr& world);

void checkRobotCollision(const CollisionRequest& req, CollisionResult& res,
const moveit::core::RobotState& state) const override;
void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
const AllowedCollisionMatrix& acm) const override;
void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state1,
const moveit::core::RobotState& state2) const override;
void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state1,
const moveit::core::RobotState& state2, const AllowedCollisionMatrix& acm) const override;

virtual double distanceRobot(const moveit::core::RobotState& state) const;
virtual double distanceRobot(const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const;
void distanceRobot(const DistanceRequest& req, DistanceResult& res,
const moveit::core::RobotState& state) const override;

void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
const moveit::core::RobotState& state) const override;
void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
const AllowedCollisionMatrix& acm) const override;
#pragma message(".h header is obsolete. Please use the .hpp")

void distanceSelf(const DistanceRequest& req, DistanceResult& res,
const moveit::core::RobotState& state) const override;
};
} // namespace collision_detection
#include <moveit/collision_detection/allvalid/collision_env_allvalid.hpp>
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Ioan Sucan, Jia Pan, Jens Petit */

#pragma once

#include <moveit/collision_detection/collision_env.hpp>

namespace collision_detection
{
/** \brief Collision environment which always just returns no collisions.
*
* This can be used to save resources if collision checking is not important. */
class CollisionEnvAllValid : public CollisionEnv
{
public:
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model, double padding = 0.0, double scale = 1.0);
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world, double padding = 0.0,
double scale = 1.0);
CollisionEnvAllValid(const CollisionEnv& other, const WorldPtr& world);

void checkRobotCollision(const CollisionRequest& req, CollisionResult& res,
const moveit::core::RobotState& state) const override;
void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
const AllowedCollisionMatrix& acm) const override;
void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state1,
const moveit::core::RobotState& state2) const override;
void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state1,
const moveit::core::RobotState& state2, const AllowedCollisionMatrix& acm) const override;

virtual double distanceRobot(const moveit::core::RobotState& state) const;
virtual double distanceRobot(const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const;
void distanceRobot(const DistanceRequest& req, DistanceResult& res,
const moveit::core::RobotState& state) const override;

void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
const moveit::core::RobotState& state) const override;
void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
const AllowedCollisionMatrix& acm) const override;

void distanceSelf(const DistanceRequest& req, DistanceResult& res,
const moveit::core::RobotState& state) const override;
};
} // namespace collision_detection
Loading
Loading