From a95364449b110056c3f3d389e1a1903cc23996ff Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Sun, 21 Jul 2024 11:03:44 +0200 Subject: [PATCH] Use the internal methods instead of using the variables directly (#1221) --- .../src/joint_trajectory_controller.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index ddcf57f508..faa2efce9b 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -43,9 +43,10 @@ JointTrajectoryController::JointTrajectoryController() controller_interface::CallbackReturn JointTrajectoryController::on_init() { - if (!urdf_.empty()) + const std::string & urdf = get_robot_description(); + if (!urdf.empty()) { - if (!model_.initString(urdf_)) + if (!model_.initString(urdf)) { RCLCPP_ERROR(get_node()->get_logger(), "Failed to parse URDF file"); } @@ -701,7 +702,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( joints_angle_wraparound_.resize(dof_); for (size_t i = 0; i < dof_; ++i) { - if (!urdf_.empty()) + if (!get_robot_description().empty()) { auto urdf_joint = model_.getJoint(params_.joints[i]); if (urdf_joint && urdf_joint->type == urdf::Joint::CONTINUOUS)