#include <GripperRequestBus.h>
Inherits AZ::EBusTraits.
|
using | BusIdType = AZ::EntityId |
|
|
virtual AZ::Outcome< void, AZStd::string > | GripperCommand (float position, float maxEffort)=0 |
|
virtual AZ::Outcome< void, AZStd::string > | CancelGripperCommand ()=0 |
|
virtual float | GetGripperPosition () const =0 |
|
virtual float | GetGripperEffort () const =0 |
|
virtual bool | IsGripperNotMoving () const =0 |
| Get if the gripper is not moving (stalled).
|
|
virtual bool | HasGripperReachedGoal () const =0 |
| Get if the gripper reached the set with GripperCommand position.
|
|
virtual bool | HasGripperCommandBeenCancelled () const =0 |
| Get if the gripper command has been cancelled.
|
|
|
static constexpr AZ::EBusAddressPolicy | AddressPolicy = AZ::EBusAddressPolicy::ById |
|
static constexpr AZ::EBusHandlerPolicy | HandlerPolicy = AZ::EBusHandlerPolicy::Single |
|
The interface allows to control gripper components through GripperCommand actions. It is a bus that allows communication between ROS2 GripperCommand Action server with the particular implementation of the gripper. It encapsulates GripperCommand commands and getters that allow to build the feedback and result messages.
- See also
- GripperCommand
◆ CancelGripperCommand()
virtual AZ::Outcome< void, AZStd::string > ROS2::GripperRequests::CancelGripperCommand |
( |
| ) |
|
|
pure virtual |
Cancel the current command to the gripper.
- Returns
- Nothing on success, error message if failed.
◆ GetGripperEffort()
virtual float ROS2::GripperRequests::GetGripperEffort |
( |
| ) |
const |
|
pure virtual |
Get the current effort of the gripper.
- Returns
- Position (gap size in meters) of the gripper.
◆ GetGripperPosition()
virtual float ROS2::GripperRequests::GetGripperPosition |
( |
| ) |
const |
|
pure virtual |
Get the current position of the gripper.
- Returns
- Position of the gripper.
◆ GripperCommand()
virtual AZ::Outcome< void, AZStd::string > ROS2::GripperRequests::GripperCommand |
( |
float |
position, |
|
|
float |
maxEffort |
|
) |
| |
|
pure virtual |
Send new command to the gripper.
- Parameters
-
position | position of the gripper (as a gap size in meters) to be set, for vacuum/electromagnetic gripper it is 0 or 1. |
maxEffort | maximum effort of the gripper to be set in Newtons. |
- Returns
- Nothing on success, error message if failed.
The documentation for this class was generated from the following file:
- Gems/ROS2/Code/Include/ROS2/Gripper/GripperRequestBus.h