You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
@pac48 Hi Paul, thank you for a great controller, the parallel gripper. I started to use it and how some feedback, improvements that we might want to consider.
1) Command interface
I found the current config confusing for the max_effort_interface, max_velocity_interface. I had to look into the code to figure out what these should be. for consistancy and also more flexibility in the future what about changing this to:
command_interfaces: [position, velocity, effort]
Then in the hpp we can use the same logic as the state_interface:
std::vector<std::string> interface_names;
for (const auto & interface : params_.state_interfaces)
{
interface_names.push_back(params_.joint + "/" + interface);
}
I would be happy to make a PR for this.
2) Effort control
Does this currently work? I had to modify the code to get effort to be forward to my motor controller, or did I have something wrongly configured? I had to add this code, some minor changes to get it working:
auto effort_command_interface_it = std::find_if(command_interfaces_.begin(), command_interfaces_.end(),
[](const hardware_interface::LoanedCommandInterface & command_interface)
{ return command_interface.get_interface_name() == hardware_interface::HW_IF_EFFORT; });
if (effort_command_interface_it == command_interfaces_.end())
{
RCLCPP_ERROR_STREAM(
get_node()->get_logger(),
"Expected 1 " << hardware_interface::HW_IF_EFFORT << " effort interface");
return controller_interface::CallbackReturn::ERROR;
}
if (effort_command_interface_it->get_prefix_name() != params_.joint)
{
RCLCPP_ERROR_STREAM(
get_node()->get_logger(), "Command interface is different than joint name `"
<< effort_command_interface_it->get_prefix_name() << "` != `"
<< params_.joint << "`");
return controller_interface::CallbackReturn::ERROR;
}
3) Hold value
Currently when we set the hold position we use this code:
Wouldn't it be better to use the effort and velocity that the user has set via an action as we would be setting the force to the max available and could be dangers as this isn't we a lot higher then the user wants?
4) Minor var renaming
Maybe rename this to be more consistent and easier to understand: joint_command_interface_ -> joint_position_command_interface_ effort_interface_ -> joint_effort_command_interface_ speed_interface_ -> joint_speed_command_interface_
As we use joint_position_state_interface_ and joint_velocity_state_interface_
At the moment it also use this syntax: command_struct_.position_cmd_ command_struct_.max_velocity_ command_struct_.max_effort_
Wouldn't this make more sense is the velocity and effort and be velocity_cmd_ and effort_cmd_ as I'm using this gripper more as force control and just limiting current.
5) not using 'max_effort'
Currently the code doesn't clamp the effort to max_effort . Which I assume is the point of the var in the parameter. I assume we should have something like this:
@pac48 Hi Paul, thank you for a great controller, the parallel gripper. I started to use it and how some feedback, improvements that we might want to consider.
1) Command interface
I found the current config confusing for the
max_effort_interface
,max_velocity_interface
. I had to look into the code to figure out what these should be. for consistancy and also more flexibility in the future what about changing this to:command_interfaces: [position, velocity, effort]
Then in the hpp we can use the same logic as the state_interface:
I would be happy to make a PR for this.
2) Effort control
Does this currently work? I had to modify the code to get effort to be forward to my motor controller, or did I have something wrongly configured? I had to add this code, some minor changes to get it working:
3) Hold value
Currently when we set the hold position we use this code:
Wouldn't it be better to use the effort and velocity that the user has set via an action as we would be setting the force to the max available and could be dangers as this isn't we a lot higher then the user wants?
4) Minor var renaming
Maybe rename this to be more consistent and easier to understand:
joint_command_interface_
->joint_position_command_interface_
effort_interface_
->joint_effort_command_interface_
speed_interface_
->joint_speed_command_interface_
As we use
joint_position_state_interface_
andjoint_velocity_state_interface_
At the moment it also use this syntax:
command_struct_.position_cmd_
command_struct_.max_velocity_
command_struct_.max_effort_
Wouldn't this make more sense is the velocity and effort and be
velocity_cmd_
andeffort_cmd_
as I'm using this gripper more as force control and just limiting current.5) not using 'max_effort'
Currently the code doesn't clamp the effort to
max_effort
. Which I assume is the point of the var in the parameter. I assume we should have something like this:Will to work and produce and PR for any of these. You can see some of these changes in this branch:
https://github.com/brennand/ros2_controllers/tree/effort_controller
Bren
The text was updated successfully, but these errors were encountered: