Skip to content

Commit

Permalink
changed member variable name for clarity
Browse files Browse the repository at this point in the history
  • Loading branch information
jodle001 committed Oct 6, 2023
1 parent 0ea6169 commit 7e3cb44
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions joint_trajectory_controller/src/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ void Trajectory::update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> j
trajectory_msg_ = joint_trajectory;
trajectory_start_time_ = static_cast<rclcpp::Time>(joint_trajectory->header.stamp);
sampled_already_ = false;
prev_start_idx_ = 0;
previous_start_index_ = 0;
}

bool Trajectory::sample(
Expand All @@ -81,7 +81,7 @@ bool Trajectory::sample(
trajectory_start_time_ = sample_time;
}

prev_start_idx_ = 0;
previous_start_index_ = 0;
sampled_already_ = true;
}

Expand Down Expand Up @@ -122,7 +122,7 @@ bool Trajectory::sample(

// time_from_start + trajectory time is the expected arrival time of trajectory
const auto last_idx = trajectory_msg_->points.size() - 1;
for (size_t i = prev_start_idx_; i < last_idx; ++i)
for (size_t i = previous_start_index_; i < last_idx; ++i)
{
auto & point = trajectory_msg_->points[i];
auto & next_point = trajectory_msg_->points[i + 1];
Expand All @@ -148,7 +148,7 @@ bool Trajectory::sample(
}
start_segment_itr = begin() + i;
end_segment_itr = begin() + (i + 1);
prev_start_idx_ = i;
previous_start_index_ = i;
return true;
}
}
Expand Down

0 comments on commit 7e3cb44

Please sign in to comment.