Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Store trajectory segment being executed and store in feedback message #605

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -223,6 +223,11 @@ class JointTrajectoryController : public controller_interface::Controller<Hardwa
ActionServerPtr action_server_;
ros::ServiceServer query_state_service_;
StatePublisherPtr state_publisher_;
/**
* @brief Indices of trajectory that is currently being executed
* @details These should usually (always?) be all the same
*/
std::vector<Scalar> trajectory_indices_;

ros::Timer goal_handle_timer_;
ros::Time last_state_publish_time_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,7 @@ bool JointTrajectoryController<SegmentImpl, HardwareInterface>::init(HardwareInt
// Initialize members
joints_.resize(n_joints);
angle_wraparound_.resize(n_joints);
trajectory_indices_ = std::vector<Scalar>(n_joints, -1);
for (unsigned int i = 0; i < n_joints; ++i)
{
// Joint handle
Expand Down Expand Up @@ -382,6 +383,9 @@ update(const ros::Time& time, const ros::Duration& period)
return;
}

// Record the index of the segment we are currently in
trajectory_indices_[i] = segment_it - curr_traj[i].begin();

// Get state error for current joint
state_joint_error_.position[0] = state_error_.position[i];
state_joint_error_.velocity[0] = state_error_.velocity[i];
Expand Down Expand Up @@ -614,6 +618,8 @@ goalCB(GoalHandle gh)

if (update_ok)
{
trajectory_indices_ = std::vector<double>(joint_names_.size(), -1);

// Accept new goal
preemptActiveGoal();
gh.setAccepted();
Expand Down Expand Up @@ -814,8 +820,8 @@ setActionFeedback()
current_active_goal->preallocated_feedback_->error.positions = state_error_.position;
current_active_goal->preallocated_feedback_->error.velocities = state_error_.velocity;
current_active_goal->preallocated_feedback_->error.time_from_start = ros::Duration(state_error_.time_from_start);
current_active_goal->preallocated_feedback_->indices = trajector_indices_;
current_active_goal->setFeedback( current_active_goal->preallocated_feedback_ );

}

template <class SegmentImpl, class HardwareInterface>
Expand Down