|
SMACC2
|
#include <cp_trajectory_history.hpp>


Public Member Functions | |
| bool | getLastTrajectory (int backIndex, moveit_msgs::msg::RobotTrajectory &trajectory) |
| bool | getLastTrajectory (moveit_msgs::msg::RobotTrajectory &trajectory) |
| void | pushTrajectory (std::string name, const moveit_msgs::msg::RobotTrajectory &trajectory, moveit_msgs::msg::MoveItErrorCodes result) |
Public Member Functions inherited from smacc2::ISmaccComponent | |
| ISmaccComponent () | |
| virtual | ~ISmaccComponent () |
| virtual std::string | getName () const |
Private Attributes | |
| std::vector< TrajectoryHistoryEntry > | trajectoryHistory_ |
Additional Inherited Members | |
Protected Member Functions inherited from smacc2::ISmaccComponent | |
| virtual void | onInitialize () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TComponent > | |
| void | requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false) |
| template<typename TComponent > | |
| void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false) |
| template<typename TClient > | |
| void | requiresClient (TClient *&requiredClientStorage) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingComponent (TArgs... targs) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingNamedComponent (std::string name, TArgs... targs) |
| rclcpp::Node::SharedPtr | getNode () |
| rclcpp::Logger | getLogger () const |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Definition at line 37 of file cp_trajectory_history.hpp.
| bool cl_move_group_interface::CpTrajectoryHistory::getLastTrajectory | ( | int | backIndex, |
| moveit_msgs::msg::RobotTrajectory & | trajectory | ||
| ) |
Definition at line 25 of file cp_trajectory_history.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and trajectoryHistory_.
Referenced by getLastTrajectory(), cl_move_group_interface::CbExecuteLastTrajectory::onEntry(), cl_move_group_interface::CbMoveLastTrajectoryInitialState::onEntry(), and cl_move_group_interface::CbUndoLastTrajectory::onEntry().


| bool cl_move_group_interface::CpTrajectoryHistory::getLastTrajectory | ( | moveit_msgs::msg::RobotTrajectory & | trajectory | ) |
Definition at line 53 of file cp_trajectory_history.cpp.
References getLastTrajectory().

| void cl_move_group_interface::CpTrajectoryHistory::pushTrajectory | ( | std::string | name, |
| const moveit_msgs::msg::RobotTrajectory & | trajectory, | ||
| moveit_msgs::msg::MoveItErrorCodes | result | ||
| ) |
Definition at line 58 of file cp_trajectory_history.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and trajectoryHistory_.
Referenced by cl_move_group_interface::CbMoveEndEffectorTrajectory::onEntry().


|
private |
Definition at line 49 of file cp_trajectory_history.hpp.
Referenced by getLastTrajectory(), and pushTrajectory().