Class CbMoveEndEffectorTrajectory

Inheritance Relationships

Base Types

  • public smacc2::SmaccAsyncClientBehavior

  • public smacc2::ISmaccUpdatable

Derived Types

Class Documentation

class CbMoveEndEffectorTrajectory : public smacc2::SmaccAsyncClientBehavior, public smacc2::ISmaccUpdatable

Subclassed by cl_move_group_interface::CbCircularPivotMotion, cl_move_group_interface::CbCircularPouringMotion, cl_move_group_interface::CbExecuteLastTrajectory, cl_move_group_interface::CbMoveCartesianRelative2, cl_move_group_interface::CbUndoLastTrajectory

Public Functions

CbMoveEndEffectorTrajectory(std::optional<std::string> tipLink = std::nullopt)
CbMoveEndEffectorTrajectory(const std::vector<geometry_msgs::msg::PoseStamped> &endEffectorTrajectory, std::optional<std::string> tipLink = std::nullopt)
template<typename TOrthogonal, typename TSourceObject>
inline void onOrthogonalAllocation()
virtual void onEntry() override
virtual void onExit() override
virtual void update() override

Public Members

std::optional<std::string> group_
std::optional<bool> allowInitialTrajectoryStateJointDiscontinuity_

Protected Functions

ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
virtual void generateTrajectory() = 0
virtual void createMarkers()
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped<tf2::Transform> &currentEndEffectorTransform)

Protected Attributes

std::vector<geometry_msgs::msg::PoseStamped> endEffectorTrajectory_
ClMoveGroup *movegroupClient_ = nullptr
visualization_msgs::msg::MarkerArray beahiorMarkers_