From b83acbb07df464a6ce01b7fac781f7fc12126cb8 Mon Sep 17 00:00:00 2001 From: mhubii Date: Tue, 3 Oct 2023 11:37:17 +0100 Subject: [PATCH] updated namespace --- .../src/joint_trajectory_executioner_node.cpp | 4 ++-- .../joint_trajectory_executioner_node.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/lbr_demos/lbr_demos_ros2_control_cpp/src/joint_trajectory_executioner_node.cpp b/lbr_demos/lbr_demos_ros2_control_cpp/src/joint_trajectory_executioner_node.cpp index bcb646bf..444d5a47 100644 --- a/lbr_demos/lbr_demos_ros2_control_cpp/src/joint_trajectory_executioner_node.cpp +++ b/lbr_demos/lbr_demos_ros2_control_cpp/src/joint_trajectory_executioner_node.cpp @@ -16,7 +16,7 @@ class LBRJointTrajectoryExecutionerNode : public rclcpp::Node { joint_trajectory_action_client_ = rclcpp_action::create_client( - this, "/position_trajectory_controller/follow_joint_trajectory"); + this, "/lbr/position_trajectory_controller/follow_joint_trajectory"); while (!joint_trajectory_action_client_->wait_for_action_server(std::chrono::seconds(1))) { RCLCPP_INFO(this->get_logger(), "Waiting for action server to become available..."); @@ -24,7 +24,7 @@ class LBRJointTrajectoryExecutionerNode : public rclcpp::Node { RCLCPP_INFO(this->get_logger(), "Action server available."); }; - void execute(const std::vector &positions, const int32_t &sec_from_start = 10) { + void execute(const std::vector &positions, const int32_t &sec_from_start = 15) { if (positions.size() != KUKA::FRI::LBRState::NUMBER_OF_JOINTS) { RCLCPP_ERROR(this->get_logger(), "Invalid number of joint positions."); return; diff --git a/lbr_demos/lbr_demos_ros2_control_python/lbr_demos_ros2_control_python/joint_trajectory_executioner_node.py b/lbr_demos/lbr_demos_ros2_control_python/lbr_demos_ros2_control_python/joint_trajectory_executioner_node.py index ca479514..bccef79f 100644 --- a/lbr_demos/lbr_demos_ros2_control_python/lbr_demos_ros2_control_python/joint_trajectory_executioner_node.py +++ b/lbr_demos/lbr_demos_ros2_control_python/lbr_demos_ros2_control_python/joint_trajectory_executioner_node.py @@ -14,13 +14,13 @@ def __init__( self.joint_trajectory_action_client_ = ActionClient( node=self, action_type=FollowJointTrajectory, - action_name="/position_trajectory_controller/follow_joint_trajectory", + action_name="/lbr/position_trajectory_controller/follow_joint_trajectory", ) while not self.joint_trajectory_action_client_.wait_for_server(1): self.get_logger().info("Waiting for action server to become available...") self.get_logger().info("Action server available.") - def execute(self, positions: list, sec_from_start: int = 10): + def execute(self, positions: list, sec_from_start: int = 15): if len(positions) != 7: self.get_logger().error("Invalid number of joint positions.") return