-
Notifications
You must be signed in to change notification settings - Fork 327
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] Enable feed-forward effort trajectories #1200
base: master
Are you sure you want to change the base?
Changes from all commits
ac8d3cb
62afca2
7b28c55
fedd208
2f68dc1
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -32,7 +32,8 @@ tl::expected<void, std::string> command_interface_type_combinations( | |
// Check if command interfaces combination is valid. Valid combinations are: | ||
// 1. effort | ||
// 2. velocity | ||
// 2. position [velocity, [acceleration]] | ||
// 3. position [velocity, [acceleration]] | ||
// 4. position, effort | ||
|
||
if ( | ||
rsl::contains<std::vector<std::string>>(interface_types, "velocity") && | ||
|
@@ -56,9 +57,12 @@ tl::expected<void, std::string> command_interface_type_combinations( | |
|
||
if ( | ||
rsl::contains<std::vector<std::string>>(interface_types, "effort") && | ||
interface_types.size() > 1) | ||
!(interface_types.size() == 1 || | ||
(interface_types.size() == 2 && | ||
rsl::contains<std::vector<std::string>>(interface_types, "position")))) | ||
Comment on lines
+60
to
+62
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this is alright but I think we'll have to reimplement this function as it's getting a little chaotic in here :D There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I agree but I'm not volunteering to open this container of invertebrates just now. Happy to file it as an issue. |
||
{ | ||
return tl::make_unexpected("'effort' command interface has to be used alone"); | ||
return tl::make_unexpected( | ||
"'effort' command interface has to be used alone or with a 'position' interface"); | ||
} | ||
|
||
return {}; | ||
|
Original file line number | Diff line number | Diff line change | ||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -276,12 +276,26 @@ controller_interface::return_type JointTrajectoryController::update( | |||||||||||||||||
// Update PIDs | ||||||||||||||||||
for (auto i = 0ul; i < dof_; ++i) | ||||||||||||||||||
{ | ||||||||||||||||||
// If effort interface only, add desired effort as feed forward | ||||||||||||||||||
// If velocity interface, ignore desired effort | ||||||||||||||||||
tmp_command_[i] = (state_desired_.velocities[i] * ff_velocity_scale_[i]) + | ||||||||||||||||||
(has_effort_command_interface_ ? state_desired_.effort[i] : 0.0) + | ||||||||||||||||||
Comment on lines
+279
to
+282
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. how are we ignoring desired effort with velocity interface here? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yup! Same doubt There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I admit this one is a not very readable. |
||||||||||||||||||
pids_[i]->computeCommand( | ||||||||||||||||||
state_error_.positions[i], state_error_.velocities[i], | ||||||||||||||||||
(uint64_t)period.nanoseconds()); | ||||||||||||||||||
} | ||||||||||||||||||
} | ||||||||||||||||||
else | ||||||||||||||||||
{ | ||||||||||||||||||
if (has_position_command_interface_ && has_effort_command_interface_) | ||||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
If we support the combinations as commented as above, this would be sufficient I guess |
||||||||||||||||||
{ | ||||||||||||||||||
for (auto i = 0ul; i < dof_; ++i) | ||||||||||||||||||
{ | ||||||||||||||||||
// If position and effort command interfaces, only pass desired effort | ||||||||||||||||||
tmp_command_[i] = state_desired_.effort[i]; | ||||||||||||||||||
} | ||||||||||||||||||
} | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
// set values for next hardware write() | ||||||||||||||||||
if (has_position_command_interface_) | ||||||||||||||||||
|
@@ -442,6 +456,11 @@ void JointTrajectoryController::read_state_from_state_interfaces(JointTrajectory | |||||||||||||||||
state.velocities.clear(); | ||||||||||||||||||
state.accelerations.clear(); | ||||||||||||||||||
} | ||||||||||||||||||
// No state interface for now, use command interface | ||||||||||||||||||
if (has_effort_command_interface_) | ||||||||||||||||||
{ | ||||||||||||||||||
assign_point_from_interface(state.effort, joint_command_interface_[3]); | ||||||||||||||||||
} | ||||||||||||||||||
Comment on lines
+459
to
+463
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Do you think it would be interesting to support effort state interfaces in the future? it would help in introspect about tracking and all. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. isn't th There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. What would be the convention for getting effort from the effort interface? |
||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajectoryPoint & state) | ||||||||||||||||||
|
@@ -510,6 +529,20 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto | |||||||||||||||||
state.accelerations.clear(); | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
// Effort state always comes from last command | ||||||||||||||||||
if (has_effort_command_interface_) | ||||||||||||||||||
{ | ||||||||||||||||||
if (interface_has_values(joint_command_interface_[3])) | ||||||||||||||||||
{ | ||||||||||||||||||
assign_point_from_interface(state.effort, joint_command_interface_[3]); | ||||||||||||||||||
} | ||||||||||||||||||
else | ||||||||||||||||||
{ | ||||||||||||||||||
state.effort.clear(); | ||||||||||||||||||
has_values = false; | ||||||||||||||||||
} | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
return has_values; | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
|
@@ -704,13 +737,14 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( | |||||||||||||||||
use_closed_loop_pid_adapter_ = | ||||||||||||||||||
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 && | ||||||||||||||||||
!params_.open_loop_control) || | ||||||||||||||||||
has_effort_command_interface_; | ||||||||||||||||||
(has_effort_command_interface_ && params_.command_interfaces.size() == 1); | ||||||||||||||||||
|
||||||||||||||||||
tmp_command_.resize(dof_, 0.0); | ||||||||||||||||||
|
||||||||||||||||||
if (use_closed_loop_pid_adapter_) | ||||||||||||||||||
{ | ||||||||||||||||||
pids_.resize(dof_); | ||||||||||||||||||
ff_velocity_scale_.resize(dof_); | ||||||||||||||||||
tmp_command_.resize(dof_, 0.0); | ||||||||||||||||||
|
||||||||||||||||||
update_pids(); | ||||||||||||||||||
} | ||||||||||||||||||
|
@@ -747,15 +781,17 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( | |||||||||||||||||
return CallbackReturn::FAILURE; | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
// effort is always used alone so no need for size check | ||||||||||||||||||
// effort only or effort and position command interfaces require position and velocity state | ||||||||||||||||||
if ( | ||||||||||||||||||
has_effort_command_interface_ && | ||||||||||||||||||
(params_.command_interfaces.size() == 1 || | ||||||||||||||||||
(params_.command_interfaces.size() == 2 && has_position_command_interface_)) && | ||||||||||||||||||
(!has_velocity_state_interface_ || !has_position_state_interface_)) | ||||||||||||||||||
{ | ||||||||||||||||||
RCLCPP_ERROR( | ||||||||||||||||||
logger, | ||||||||||||||||||
"'effort' command interface can only be used alone if 'velocity' and " | ||||||||||||||||||
"'position' state interfaces are present"); | ||||||||||||||||||
"'effort' command interface can only be used alone or with 'position' command interface " | ||||||||||||||||||
"if 'velocity' and 'position' state interfaces are present"); | ||||||||||||||||||
return CallbackReturn::FAILURE; | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
|
@@ -1214,6 +1250,10 @@ void JointTrajectoryController::compute_error_for_joint( | |||||||||||||||||
{ | ||||||||||||||||||
error.accelerations[index] = desired.accelerations[index] - current.accelerations[index]; | ||||||||||||||||||
} | ||||||||||||||||||
if (has_effort_command_interface_) | ||||||||||||||||||
{ | ||||||||||||||||||
error.effort[index] = desired.effort[index]; | ||||||||||||||||||
} | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
void JointTrajectoryController::fill_partial_goal( | ||||||||||||||||||
|
@@ -1463,10 +1503,12 @@ bool JointTrajectoryController::validate_trajectory_msg( | |||||||||||||||||
return false; | ||||||||||||||||||
} | ||||||||||||||||||
// reject effort entries | ||||||||||||||||||
if (!points[i].effort.empty()) | ||||||||||||||||||
if (!has_effort_command_interface_ && !points[i].effort.empty()) | ||||||||||||||||||
{ | ||||||||||||||||||
RCLCPP_ERROR( | ||||||||||||||||||
get_node()->get_logger(), "Trajectories with effort fields are currently not supported."); | ||||||||||||||||||
get_node()->get_logger(), | ||||||||||||||||||
"Trajectories with effort fields are only supported for " | ||||||||||||||||||
"controllers using the 'effort' command interface."); | ||||||||||||||||||
return false; | ||||||||||||||||||
} | ||||||||||||||||||
Comment on lines
+1506
to
1513
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Should we do something if there is effort_command_interface and the points with empty effort?, should we at least print one time warning? or not needed? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I would argue that for backward compatibility we shouldn't print warnings. Previously the effort command interface accepted position-only or position+velocity trajectories without warnings. It would start printing warnings for completely valid trajectories. |
||||||||||||||||||
} | ||||||||||||||||||
|
@@ -1537,6 +1579,7 @@ void JointTrajectoryController::resize_joint_trajectory_point( | |||||||||||||||||
{ | ||||||||||||||||||
point.accelerations.resize(size, 0.0); | ||||||||||||||||||
} | ||||||||||||||||||
point.effort.resize(size, 0.0); | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
void JointTrajectoryController::resize_joint_trajectory_point_command( | ||||||||||||||||||
|
@@ -1605,6 +1648,10 @@ void JointTrajectoryController::init_hold_position_msg() | |||||||||||||||||
// add velocity, so that trajectory sampling returns acceleration points in any case | ||||||||||||||||||
hold_position_msg_ptr_->points[0].accelerations.resize(dof_, 0.0); | ||||||||||||||||||
} | ||||||||||||||||||
if (has_effort_command_interface_) | ||||||||||||||||||
{ | ||||||||||||||||||
hold_position_msg_ptr_->points[0].effort.resize(dof_, 0.0); | ||||||||||||||||||
} | ||||||||||||||||||
} | ||||||||||||||||||
|
||||||||||||||||||
} // namespace joint_trajectory_controller | ||||||||||||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can't the same be used with the combination of
velocity, effort
andposition, velocity, and effort
?. Ofcourse, given that there is no closed-loop optionuse_closed_loop_pid_adapter_
selected.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I suppose it could work. The logic to switch what is calculated via PIDs and what comes from the desired effort would need a bit of thought. I don't have a use case for this though. Position+effort is very common for manipulation where you need to add that extra force to maintain contact. I've only used velocity control for an arm that had a very low control rate and for wheeled robots, neither of which needed feed forward effort.