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

CPP Best Practices #2691

Closed
wants to merge 18 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion moveit_core/exceptions/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,4 @@ ament_target_dependencies(moveit_exceptions Boost rclcpp urdfdom
urdfdom_headers)
target_link_libraries(moveit_exceptions moveit_utils)

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_exceptions)
2 changes: 1 addition & 1 deletion moveit_core/kinematic_constraints/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ target_link_libraries(
moveit_kinematic_constraints moveit_collision_detection_fcl
moveit_kinematics_base moveit_robot_state moveit_robot_model moveit_utils)

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_kinematic_constraints)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/kinematics_metrics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,4 @@ ament_target_dependencies(moveit_kinematics_metrics urdf urdfdom_headers
target_link_libraries(moveit_kinematics_metrics moveit_robot_model
moveit_robot_state moveit_utils)

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_kinematics_metrics)
2 changes: 1 addition & 1 deletion moveit_core/macros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@ target_include_directories(
moveit_macros INTERFACE $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/moveit_core>)

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_macros)
6 changes: 3 additions & 3 deletions moveit_core/online_signal_smoothing/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,11 +54,11 @@ ament_target_dependencies(
# Installation
install(DIRECTORY include/ DESTINATION include/moveit_core)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_smoothing_base_export.h
DESTINATION include/moveit_core)
DESTINATION include/moveit_core_online_signal_smoothing)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_butterworth_filter_export.h
DESTINATION include/moveit_core)
DESTINATION include/moveit_core_online_signal_smoothing)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_acceleration_filter_export.h
DESTINATION include/moveit_core)
DESTINATION include/moveit_core_online_signal_smoothing)

# Testing

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,4 @@ ament_target_dependencies(moveit_planning_interface moveit_msgs urdf urdfdom
target_link_libraries(moveit_planning_interface moveit_robot_trajectory
moveit_robot_state moveit_planning_scene moveit_utils)

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_planning_interface)
4 changes: 2 additions & 2 deletions moveit_core/planning_scene/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@ target_link_libraries(
moveit_trajectory_processing
moveit_utils)

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_planning_scene)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_planning_scene_export.h
DESTINATION include/moveit_core)
DESTINATION include/moveit_core_planning_scene)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,4 +48,4 @@ if(BUILD_TESTING)
target_link_libraries(test_robot_model moveit_test_utils moveit_robot_model)
endif()

install(DIRECTORY include/ DESTINATION include/moveit_core)
install(DIRECTORY include/ DESTINATION include/moveit_core_robot_model)
Original file line number Diff line number Diff line change
Expand Up @@ -46,40 +46,40 @@

static const std::string ROBOT_DESCRIPTION = "robot_description";

/** \brief Factor to compute the maximum number of trials random clutter generation. */
// \brief Factor to compute the maximum number of trials random clutter generation.
static const int MAX_SEARCH_FACTOR_CLUTTER = 3;

/** \brief Factor to compute the maximum number of trials for random state generation. */
// \brief Factor to compute the maximum number of trials for random state generation.
static const int MAX_SEARCH_FACTOR_STATES = 30;

/** \brief Defines a random robot state. */
// \brief Defines a random robot state.
enum class RobotStateSelector
{
IN_COLLISION,
NOT_IN_COLLISION,
RANDOM,
};

/** \brief Enumerates the available collision detectors. */
// \brief Enumerates the available collision detectors.
enum class CollisionDetector
{
FCL,
BULLET,
};

/** \brief Enumerates the different types of collision objects. */
// \brief Enumerates the different types of collision objects.
enum class CollisionObjectType
{
MESH,
BOX,
};

/** \brief Clutters the world of the planning scene with random objects in a certain area around the origin. All added
* objects are not in collision with the robot.
*
* \param planning_scene The planning scene
* \param num_objects The number of objects to be cluttered
* \param CollisionObjectType Type of object to clutter (mesh or box) */
// \brief Clutters the world of the planning scene with random objects in a certain area around the origin. All added
// objects are not in collision with the robot.
//
// \param planning_scene The planning scene
// \param num_objects The number of objects to be cluttered
// \param CollisionObjectType Type of object to clutter (mesh or box)
void clutterWorld(const planning_scene::PlanningScenePtr& planning_scene, const size_t num_objects,
CollisionObjectType type)
{
Expand Down Expand Up @@ -164,12 +164,12 @@ void clutterWorld(const planning_scene::PlanningScenePtr& planning_scene, const
ROS_INFO_STREAM("Cluttered the planning scene with " << added_objects << " objects");
}

/** \brief Runs a collision detection benchmark and measures the time.
*
* \param trials The number of repeated collision checks for each state
* \param scene The planning scene
* \param CollisionDetector The type of collision detector
* \param only_self Flag for only self collision check performed */
// \brief Runs a collision detection benchmark and measures the time.
//
// \param trials The number of repeated collision checks for each state
// \param scene The planning scene
// \param CollisionDetector The type of collision detector
// \param only_self Flag for only self collision check performed
void runCollisionDetection(unsigned int trials, const planning_scene::PlanningScenePtr& scene,
const std::vector<moveit::core::RobotState>& states, const CollisionDetector col_detector,
bool only_self, bool distance = false)
Expand Down Expand Up @@ -242,11 +242,11 @@ void runCollisionDetection(unsigned int trials, const planning_scene::PlanningSc
scene->setCurrentState(states.back());
}

/** \brief Samples valid states of the robot which can be in collision if desired.
* \param desired_states Specifier for type for desired state
* \param num_states Number of desired states
* \param scene The planning scene
* \param robot_states Result vector */
//\brief Samples valid states of the robot which can be in collision if desired.
//\param desired_states Specifier for type for desired state
//\param num_states Number of desired states
//\param scene The planning scene
//\param robot_states Result vector
void findStates(const RobotStateSelector desired_states, unsigned int num_states,
const planning_scene::PlanningScenePtr& scene, std::vector<moveit::core::RobotState>& robot_states)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ int main(int argc, char** argv)
if (valid)
{
bool found = false;
unsigned int attempts = 0;
unsigned int attempts{ 0 };
do
{
attempts++;
Expand All @@ -121,7 +121,7 @@ int main(int argc, char** argv)
else if (invalid)
{
bool found = false;
unsigned int attempts = 0;
unsigned int attempts{ 0 };
do
{
attempts++;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ bool ModifiedUrdfConfig::hasChanges() const
{
// Returns true if any of the included xacros are configured and have individually changed
// or the list of included xacros have changed.
unsigned int count = 0;
unsigned int count{ 0 };
for (auto& pair : getIncludedXacroMap())
{
if (!pair.second->isConfigured())
Expand Down