Open 3D Engine ROS2 Gem API Reference 23.10.0
O3DE is an open-source, fully-featured, high-fidelity, modular 3D engine for building games and simulations, available to every industry.
ROS2::FollowJointTrajectoryActionServer Class Reference

#include <FollowJointTrajectoryActionServer.h>

Public Types

using FollowJointTrajectory = control_msgs::action::FollowJointTrajectory
 

Public Member Functions

 FollowJointTrajectoryActionServer (const AZStd::string &actionName, const AZ::EntityId &entityId)
 
JointsTrajectoryRequests::TrajectoryActionStatus GetGoalStatus () const
 
void CancelGoal (std::shared_ptr< FollowJointTrajectory::Result > result)
 
void SetGoalSuccess ()
 Sets the goal status to success.
 
void GoalSuccess (std::shared_ptr< FollowJointTrajectory::Result > result)
 
void PublishFeedback (std::shared_ptr< FollowJointTrajectory::Feedback > feedback)
 

Detailed Description

A class wrapping ROS 2 action server for joint trajectory controller.

See also
joint trajectory controller .

Constructor & Destructor Documentation

◆ FollowJointTrajectoryActionServer()

ROS2::FollowJointTrajectoryActionServer::FollowJointTrajectoryActionServer ( const AZStd::string &  actionName,
const AZ::EntityId &  entityId 
)

Create an action server for FollowJointTrajectory action and bind Goal callbacks.

Parameters
actionNameName of the action, similar to topic or service name.
entityIdentity which will execute callbacks through JointsTrajectoryRequestBus.
See also
ROS 2 action server documentation

Member Function Documentation

◆ CancelGoal()

void ROS2::FollowJointTrajectoryActionServer::CancelGoal ( std::shared_ptr< FollowJointTrajectory::Result >  result)

Cancel the current goal.

Parameters
resultResult to be passed to through action server to the client.

◆ GetGoalStatus()

JointsTrajectoryRequests::TrajectoryActionStatus ROS2::FollowJointTrajectoryActionServer::GetGoalStatus ( ) const

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
resultResult which contains success code.

◆ PublishFeedback()

void ROS2::FollowJointTrajectoryActionServer::PublishFeedback ( std::shared_ptr< FollowJointTrajectory::Feedback >  feedback)

Publish feedback during an active action.

Parameters
feedbackAn action feedback message informing about the progress.

The documentation for this class was generated from the following file: