-
Notifications
You must be signed in to change notification settings - Fork 563
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
collision_distance_field, port to ROS 2 #65
Changes from 13 commits
a61f85e
6eb216e
39d9a67
70e566b
8f25b8f
f874662
81a66cc
c548aa8
7077bf2
ad96e04
86c82b3
6fc6693
2449e1e
65137db
7edf376
7f4b0e5
4cd53f4
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,11 +1,6 @@ | ||
set(MOVEIT_LIB_NAME moveit_collision_distance_field) | ||
|
||
if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") | ||
# clang is picky about new virtual functions hiding existing ones | ||
add_compile_options(-Wno-overloaded-virtual) | ||
endif() | ||
|
||
add_library(${MOVEIT_LIB_NAME} | ||
add_library(${MOVEIT_LIB_NAME} SHARED | ||
src/collision_distance_field_types.cpp | ||
src/collision_common_distance_field.cpp | ||
src/collision_robot_distance_field.cpp | ||
|
@@ -14,23 +9,54 @@ add_library(${MOVEIT_LIB_NAME} | |
src/collision_world_hybrid.cpp | ||
) | ||
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") | ||
target_link_libraries(${MOVEIT_LIB_NAME} | ||
moveit_planning_scene moveit_distance_field | ||
${catkin_LIBRARIES} ${Boost_LIBRARIES}) | ||
add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) | ||
|
||
if(CATKIN_ENABLE_TESTING) | ||
find_package(moveit_resources REQUIRED) | ||
include_directories(${moveit_resources_INCLUDE_DIRS}) | ||
|
||
catkin_add_gtest(test_collision_distance_field test/test_collision_distance_field.cpp) | ||
target_link_libraries(test_collision_distance_field ${MOVEIT_LIB_NAME}) | ||
endif() | ||
ament_target_dependencies(${MOVEIT_LIB_NAME} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. please fix white space. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. |
||
moveit_planning_scene | ||
moveit_distance_field | ||
urdf | ||
visualization_msgs | ||
tf2_eigen | ||
angles | ||
) | ||
|
||
target_link_libraries(${MOVEIT_LIB_NAME} | ||
moveit_planning_scene | ||
moveit_distance_field | ||
moveit_collision_detection | ||
moveit_robot_state | ||
${geometric_shapes_LIBRARIES} | ||
) | ||
|
||
install(TARGETS ${MOVEIT_LIB_NAME} | ||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | ||
LIBRARY DESTINATION lib | ||
ARCHIVE DESTINATION lib | ||
) | ||
|
||
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) | ||
install(DIRECTORY include/ DESTINATION include) | ||
|
||
if(BUILD_TESTING) | ||
find_package(ament_cmake_gtest REQUIRED) | ||
find_package(moveit_resources REQUIRED) | ||
include_directories(${moveit_resources_INCLUDE_DIRS}) | ||
find_package(resource_retriever REQUIRED) | ||
|
||
if(WIN32) | ||
# TODO add windows paths | ||
else() | ||
set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../planning_scene;${CMAKE_CURRENT_BINARY_DIR}/../distance_field;${CMAKE_CURRENT_BINARY_DIR}/../collision_detection;${CMAKE_CURRENT_BINARY_DIR}/../robot_state;${CMAKE_CURRENT_BINARY_DIR}/../robot_model;${CMAKE_CURRENT_BINARY_DIR}/../utils") | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Add TODO for fixing this and assign to yourself. Otherwise, we will likely forget to get back to this |
||
endif() | ||
|
||
ament_add_gtest(test_collision_distance_field test/test_collision_distance_field.cpp) | ||
target_link_libraries(test_collision_distance_field | ||
${MOVEIT_LIB_NAME} | ||
moveit_collision_detection | ||
moveit_collision_distance_field | ||
moveit_robot_state | ||
${geometric_shapes_LIBRARIES} | ||
${OCTOMAP_LIBRARIES} | ||
${srdfdom_LIBRARIES} | ||
resource_retriever::resource_retriever | ||
moveit_distance_field | ||
moveit_planning_scene | ||
) | ||
endif() |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -51,11 +51,16 @@ | |
#include <moveit/macros/class_forward.h> | ||
#include <moveit/distance_field/distance_field.h> | ||
#include <moveit/distance_field/propagation_distance_field.h> | ||
#include <visualization_msgs/MarkerArray.h> | ||
#include <ros/console.h> | ||
#include <visualization_msgs/msg/marker_array.hpp> | ||
#include "rclcpp/clock.hpp" | ||
#include "rclcpp/rclcpp.hpp" | ||
#include "rclcpp/time.hpp" | ||
#include "rclcpp/utilities.hpp" | ||
|
||
|
||
namespace collision_detection | ||
{ | ||
static rclcpp::Logger LOGGER_COLLISION_DISTANCE_FIELD = rclcpp::get_logger("moveit").get_child("collision_distance_field"); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. clang There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. |
||
enum CollisionType | ||
{ | ||
NONE = 0, | ||
|
@@ -406,7 +411,7 @@ class PosedBodySphereDecompositionVector | |
{ | ||
if (i >= decomp_vector_.size()) | ||
{ | ||
ROS_INFO_NAMED("collision_distance_field", "No body decomposition"); | ||
mlautman marked this conversation as resolved.
Show resolved
Hide resolved
|
||
RCLCPP_INFO(LOGGER_COLLISION_DISTANCE_FIELD, "No body decomposition"); | ||
return empty_ptr_; | ||
} | ||
return decomp_vector_[i]; | ||
|
@@ -416,7 +421,7 @@ class PosedBodySphereDecompositionVector | |
{ | ||
if (ind >= decomp_vector_.size()) | ||
{ | ||
ROS_WARN_NAMED("collision_distance_field", "Can't update pose"); | ||
RCLCPP_WARN(LOGGER_COLLISION_DISTANCE_FIELD, "Can't update pose"); | ||
return; | ||
} | ||
decomp_vector_[ind]->updatePose(pose); | ||
|
@@ -469,7 +474,7 @@ class PosedBodyPointDecompositionVector | |
{ | ||
if (i >= decomp_vector_.size()) | ||
{ | ||
ROS_INFO_NAMED("collision_distance_field", "No body decomposition"); | ||
RCLCPP_INFO(LOGGER_COLLISION_DISTANCE_FIELD, "No body decomposition"); | ||
return empty_ptr_; | ||
} | ||
return decomp_vector_[i]; | ||
|
@@ -483,7 +488,7 @@ class PosedBodyPointDecompositionVector | |
} | ||
else | ||
{ | ||
ROS_WARN_NAMED("collision_distance_field", "Can't update pose"); | ||
RCLCPP_WARN(LOGGER_COLLISION_DISTANCE_FIELD, "Can't update pose"); | ||
return; | ||
} | ||
} | ||
|
@@ -509,20 +514,20 @@ struct ProximityInfo | |
bool doBoundingSpheresIntersect(const PosedBodySphereDecompositionConstPtr& p1, | ||
const PosedBodySphereDecompositionConstPtr& p2); | ||
|
||
void getCollisionSphereMarkers(const std_msgs::ColorRGBA& color, const std::string& frame_id, const std::string& ns, | ||
const ros::Duration& dur, | ||
void getCollisionSphereMarkers(const std_msgs::msg::ColorRGBA& color, const std::string& frame_id, const std::string& ns, | ||
const rclcpp::Duration& dur, | ||
const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions, | ||
visualization_msgs::MarkerArray& arr); | ||
visualization_msgs::msg::MarkerArray& arr); | ||
|
||
void getProximityGradientMarkers(const std::string& frame_id, const std::string& ns, const ros::Duration& dur, | ||
void getProximityGradientMarkers(const std::string& frame_id, const std::string& ns, const rclcpp::Duration& dur, | ||
const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions, | ||
const std::vector<PosedBodySphereDecompositionVectorPtr>& posed_vector_decompositions, | ||
const std::vector<GradientInfo>& gradients, visualization_msgs::MarkerArray& arr); | ||
const std::vector<GradientInfo>& gradients, visualization_msgs::msg::MarkerArray& arr); | ||
|
||
void getCollisionMarkers(const std::string& frame_id, const std::string& ns, const ros::Duration& dur, | ||
void getCollisionMarkers(const std::string& frame_id, const std::string& ns, const rclcpp::Duration& dur, | ||
const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions, | ||
const std::vector<PosedBodySphereDecompositionVectorPtr>& posed_vector_decompositions, | ||
const std::vector<GradientInfo>& gradients, visualization_msgs::MarkerArray& arr); | ||
const std::vector<GradientInfo>& gradients, visualization_msgs::msg::MarkerArray& arr); | ||
} | ||
|
||
#endif |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why are we removing this. It is only a warning. Rather than remove, we should mark the overloaded functions as virtual and the overloading functions as override