Skip to content

Commit

Permalink
Use the internal methods instead of using the variables directly (#1221)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jul 21, 2024
1 parent 990bfb6 commit a953644
Showing 1 changed file with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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");
}
Expand Down Expand Up @@ -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)
Expand Down

0 comments on commit a953644

Please sign in to comment.