#include <FollowJointTrajectoryActionServer.h>
|
using | FollowJointTrajectory = control_msgs::action::FollowJointTrajectory |
|
A class wrapping ROS 2 action server for joint trajectory controller.
- See also
- joint trajectory controller .
◆ FollowJointTrajectoryActionServer()
ROS2::FollowJointTrajectoryActionServer::FollowJointTrajectoryActionServer |
( |
const AZStd::string & |
actionName, |
|
|
const AZ::EntityId & |
entityId |
|
) |
| |
Create an action server for FollowJointTrajectory action and bind Goal callbacks.
- Parameters
-
actionName | Name of the action, similar to topic or service name. |
entityId | entity which will execute callbacks through JointsTrajectoryRequestBus. |
- See also
- ROS 2 action server documentation
◆ CancelGoal()
void ROS2::FollowJointTrajectoryActionServer::CancelGoal |
( |
std::shared_ptr< FollowJointTrajectory::Result > |
result | ) |
|
Cancel the current goal.
- Parameters
-
result | Result to be passed to through action server to the client. |
◆ GetGoalStatus()
Return trajectory action status.
- Returns
- Status of the trajectory execution.
◆ GoalSuccess()
void ROS2::FollowJointTrajectoryActionServer::GoalSuccess |
( |
std::shared_ptr< FollowJointTrajectory::Result > |
result | ) |
|
Report goal success to the action server.
- Parameters
-
result | Result which contains success code. |
◆ PublishFeedback()
void ROS2::FollowJointTrajectoryActionServer::PublishFeedback |
( |
std::shared_ptr< FollowJointTrajectory::Feedback > |
feedback | ) |
|
Publish feedback during an active action.
- Parameters
-
feedback | An action feedback message informing about the progress. |
The documentation for this class was generated from the following file:
- Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.h