Skip to content

Commit

Permalink
rename parameters and fix cmake format
Browse files Browse the repository at this point in the history
Signed-off-by: Paul Gesel <paulgesel@gmail.com>
  • Loading branch information
pac48 committed Jan 18, 2024
1 parent 6484cd9 commit ea7ce4c
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 18 deletions.
4 changes: 2 additions & 2 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,9 @@ install(
TARGETS
collision_detector_bullet_plugin
moveit_acceleration_filter
moveit_acceleration_parameters
moveit_acceleration_filter_parameters
moveit_butterworth_filter
moveit_butterworth_parameters
moveit_butterworth_filter_parameters
moveit_collision_detection
moveit_collision_detection_bullet
moveit_collision_detection_fcl
Expand Down
28 changes: 14 additions & 14 deletions moveit_core/online_signal_smoothing/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,10 @@ set_target_properties(moveit_butterworth_filter PROPERTIES VERSION
"${${PROJECT_NAME}_VERSION}"
)

generate_parameter_library(moveit_butterworth_parameters src/butterworth_parameters.yaml)
generate_parameter_library(moveit_butterworth_filter_parameters src/butterworth_parameters.yaml)

target_link_libraries(moveit_butterworth_filter
moveit_butterworth_parameters
moveit_butterworth_filter_parameters
moveit_robot_model
moveit_smoothing_base
)
Expand All @@ -46,26 +46,26 @@ ament_target_dependencies(moveit_butterworth_filter
)

add_library(moveit_acceleration_filter SHARED
src/acceleration_filter.cpp
)
src/acceleration_filter.cpp
)
generate_export_header(moveit_acceleration_filter)
target_include_directories(moveit_acceleration_filter PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>
$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>
)
set_target_properties(moveit_acceleration_filter PROPERTIES VERSION
"${${PROJECT_NAME}_VERSION}"
"${${PROJECT_NAME}_VERSION}"
)

generate_parameter_library(moveit_acceleration_parameters src/acceleration_parameters.yaml)
generate_parameter_library(moveit_acceleration_filter_parameters src/acceleration_parameters.yaml)

target_link_libraries(moveit_acceleration_filter
moveit_acceleration_parameters
moveit_robot_state
moveit_smoothing_base
osqp::osqp
moveit_acceleration_filter_parameters
moveit_robot_state
moveit_smoothing_base
osqp::osqp
)
ament_target_dependencies(moveit_acceleration_filter
srdfdom # include dependency from moveit_robot_model
srdfdom # include dependency from moveit_robot_model
)


Expand All @@ -77,7 +77,7 @@ install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_acceleration_filter_export.h DE

# Testing

if(BUILD_TESTING)
if (BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gtest REQUIRED)

Expand All @@ -88,4 +88,4 @@ if(BUILD_TESTING)
# Acceleration filter unit test
ament_add_gtest(test_acceleration_filter test/test_acceleration_filter.cpp)
target_link_libraries(test_acceleration_filter moveit_acceleration_filter moveit_test_utils)
endif()
endif ()
2 changes: 1 addition & 1 deletion moveit_core/online_signal_smoothing/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@ In the figures, the red arrows show the displacement that will occur given the c

- Figure A: The desired position is within the acceleration limits. The next commanded point will be exactly the desired point.
- Figure B: The line between the current position and the desired position intersects the acceleration limits, but the reference position is not within the bounds. The next commanded point will be the point on the displacement line that is closest to the reference.
- Figure C: Neither the displacement line intersects the acceleration limits nor does the reference point lie within the limits. In this case, the next commanded point will be the one that minimizes the robot's velocity while maintaining its direction.
- Figure C: Neither the displacement line intersects the acceleration limits nor does the reference point lie within the limits. In this case, the next commanded point will be the one that minimizes the robot's velocity while maintaining its direction.
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ c --------x--- v |
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit/utils/logger.hpp>
#include <moveit_acceleration_parameters.hpp>
#include <moveit_acceleration_filter_parameters.hpp>

#include <osqp.h>
#include <types.h>
Expand Down

0 comments on commit ea7ce4c

Please sign in to comment.