Skip to content

Commit

Permalink
update parameter name
Browse files Browse the repository at this point in the history
Signed-off-by: Paul Gesel <[email protected]>
  • Loading branch information
pac48 committed Feb 15, 2024
1 parent 61a3fee commit 114012b
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -108,15 +108,16 @@ void GripperActionController::accepted_callback(
// This is the non-realtime command_struct
// We use command_ for sharing
command_struct_.position_cmd_ = goal_handle->get_goal()->command.position[0];
if (params_.use_velocity_interface && !goal_handle->get_goal()->command.velocity.empty())
if (
params_.configure_max_velocity_interface && !goal_handle->get_goal()->command.velocity.empty())
{
command_struct_.max_velocity_ = goal_handle->get_goal()->command.velocity[0];
}
else
{
command_struct_.max_velocity_ = params_.max_velocity;
}
if (params_.use_effort_interface && !goal_handle->get_goal()->command.effort.empty())
if (params_.configure_max_effort_interface && !goal_handle->get_goal()->command.effort.empty())
{
command_struct_.max_effort_ = goal_handle->get_goal()->command.effort[0];
}
Expand Down Expand Up @@ -364,11 +365,11 @@ controller_interface::InterfaceConfiguration
GripperActionController::command_interface_configuration() const
{
std::vector<std::string> names = {params_.joint + "/" + hardware_interface::HW_IF_POSITION};
if (params_.use_effort_interface)
if (params_.configure_max_effort_interface)
{
names.push_back({params_.joint + "/set_gripper_max_effort"});
}
if (params_.use_velocity_interface)
if (params_.configure_max_velocity_interface)
{
names.push_back({params_.joint + "/set_gripper_max_velocity"});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,12 +49,12 @@ antipodal_gripper_action_controller:
description: "stall timeout",
default_value: 1.0,
}
use_effort_interface: {
configure_max_effort_interface: {
type: bool,
description: "Controller will claim the {joint}/gripper_effort interface if true.",
default_value: false,
}
use_velocity_interface: {
configure_max_velocity_interface: {
type: bool,
description: "Controller will claim the {joint}/gripper_speed interface if true.",
default_value: false,
Expand Down

0 comments on commit 114012b

Please sign in to comment.