Skip to content

Commit 9308f22

Browse files
committed
renamed motion_primitives_forward_controller package to motion_primitives_controllers
1 parent 7f9a782 commit 9308f22

File tree

5 files changed

+10
-10
lines changed

5 files changed

+10
-10
lines changed

ur_robot_driver/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ find_package(tf2_geometry_msgs REQUIRED)
3838
find_package(ur_client_library REQUIRED)
3939
find_package(ur_dashboard_msgs REQUIRED)
4040
find_package(ur_msgs REQUIRED)
41-
find_package(motion_primitives_forward_controller REQUIRED)
41+
find_package(motion_primitives_controllers REQUIRED)
4242
find_package(control_msgs REQUIRED)
4343

4444
include_directories(include)
@@ -64,7 +64,7 @@ target_link_libraries(ur_robot_driver_plugin PUBLIC
6464
rclcpp::rclcpp
6565
rclcpp_lifecycle::rclcpp_lifecycle
6666
ur_client_library::urcl
67-
motion_primitives_forward_controller::motion_primitives_forward_controller
67+
motion_primitives_controllers::motion_primitives_controllers
6868
)
6969
target_include_directories(
7070
ur_robot_driver_plugin

ur_robot_driver/config/ur_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ controller_manager:
5151
enforce_command_limits: false
5252

5353
motion_primitive_forward_controller:
54-
type: motion_primitives_forward_controller/MotionPrimitivesForwardController
54+
type: motion_primitives_controllers/MotionPrimitivesForwardController
5555

5656
speed_scaling_state_broadcaster:
5757
ros__parameters:

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
* \date 2019-04-11
3636
*
3737
* \author Mathias Fuhrer [email protected]
38-
* \date 2025-05-28 – Added support for usage with motion_primitives_forward_controller
38+
* \date 2025-05-28 – Added support for usage with motion_primitives_controller
3939
*
4040
*/
4141
//----------------------------------------------------------------------
@@ -72,10 +72,10 @@
7272
#include <realtime_tools/lock_free_queue.hpp>
7373

7474
// Motion primitives controller
75-
#include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp"
75+
#include "motion_primitives_controllers/motion_primitives_forward_controller.hpp"
7676

7777
using MoprimMotionType = control_msgs::msg::MotionPrimitive;
78-
using MoprimMotionHelperType = motion_primitives_forward_controller::MotionHelperType;
78+
using MoprimMotionHelperType = motion_primitives_controllers::MotionHelperType;
7979

8080
namespace ur_robot_driver
8181
{
@@ -299,7 +299,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
299299

300300
// Status for communication with controller
301301
bool motion_primitives_forward_controller_running_;
302-
using MoprimExecutionState = motion_primitives_forward_controller::ExecutionState;
302+
using MoprimExecutionState = motion_primitives_controllers::ExecutionState;
303303
std::atomic<MoprimExecutionState> current_moprim_execution_status_;
304304
std::atomic_bool ready_for_new_moprim_;
305305

ur_robot_driver/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@
4848
<depend>ur_dashboard_msgs</depend>
4949
<depend>ur_description</depend>
5050
<depend>ur_msgs</depend>
51-
<depend>motion_primitives_forward_controller</depend>
51+
<depend>motion_primitives_controllers</depend>
5252
<depend>control_msgs</depend>
5353

5454
<exec_depend>force_torque_sensor_broadcaster</exec_depend>

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
* \date 2020-11-9
3636
*
3737
* \author Mathias Fuhrer [email protected]
38-
* \date 2025-05-28 – Added support for usage with motion_primitives_forward_controller
38+
* \date 2025-05-28 – Added support for usage with motion_primitives_controller
3939
*
4040
*/
4141
//----------------------------------------------------------------------
@@ -1630,7 +1630,7 @@ void URPositionHardwareInterface::handleMoprimCommands()
16301630
}
16311631
default:
16321632
{
1633-
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Received moprim command");
1633+
RCLCPP_DEBUG(rclcpp::get_logger("URPositionHardwareInterface"), "Received moprim command");
16341634
// Push command to thread-safe queue
16351635
if (!moprim_cmd_queue_.push(hw_moprim_commands_)) {
16361636
RCLCPP_ERROR(rclcpp::get_logger("URPositionHardwareInterface"), "Failed to push command to "

0 commit comments

Comments
 (0)