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

[JTC] When replacing trajectories in open-loop mode use time of the last command when setting point of trajectory before msg. #780

Open
wants to merge 3 commits into
base: master
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 @@ -126,6 +126,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
Params params_;

trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
rclcpp::Time last_commanded_time_;
/// Specify interpolation method. Default to splines.
interpolation_methods::InterpolationMethod interpolation_method_{
interpolation_methods::DEFAULT_INTERPOLATION};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,8 +186,12 @@ controller_interface::return_type JointTrajectoryController::update(
first_sample = true;
if (params_.open_loop_control)
{
if (last_commanded_time_.seconds() == 0.0)
{
last_commanded_time_ = time;
}
traj_external_point_ptr_->set_point_before_trajectory_msg(
time, last_commanded_state_, joints_angle_wraparound_);
last_commanded_time_, last_commanded_state_, joints_angle_wraparound_);
}
else
{
Expand Down Expand Up @@ -310,6 +314,7 @@ controller_interface::return_type JointTrajectoryController::update(

// store the previous command. Used in open-loop control mode
last_commanded_state_ = state_desired_;
last_commanded_time_ = time;
}

if (active_goal)
Expand Down Expand Up @@ -937,6 +942,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
read_state_from_state_interfaces(state_current_);
read_state_from_state_interfaces(last_commanded_state_);
}
last_commanded_time_ = rclcpp::Time();

// The controller should start by holding position at the beginning of active state
add_new_trajectory_msg(set_hold_position());
Expand Down
Loading