SMACC2
Loading...
Searching...
No Matches
cl_moveit2z::CpTrajectoryHistory Class Reference

#include <cp_trajectory_history.hpp>

Inheritance diagram for cl_moveit2z::CpTrajectoryHistory:
Inheritance graph
Collaboration diagram for cl_moveit2z::CpTrajectoryHistory:
Collaboration graph

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)
 
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< TrajectoryHistoryEntrytrajectoryHistory_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
virtual void onInitialize ()
 
template<typename TOrthogonal , typename TClient >
void onComponentInitialization ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
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
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 37 of file cp_trajectory_history.hpp.

Member Function Documentation

◆ getLastTrajectory() [1/4]

bool cl_moveit2z::CpTrajectoryHistory::getLastTrajectory ( int backIndex,
moveit_msgs::msg::RobotTrajectory & trajectory )
inline

Definition at line 40 of file cp_trajectory_history.hpp.

41 {
42 if (trajectoryHistory_.size() == 0)
43 {
44 RCLCPP_WARN_STREAM(
45 getLogger(), "[" << getName() << "] requested index: " << backIndex
46 << ", history size: " << trajectoryHistory_.size());
47 return false;
48 }
49
50 if (backIndex < 0)
51 {
52 backIndex = 0;
53 }
54 else if ((size_t)backIndex >= this->trajectoryHistory_.size())
55 {
56 RCLCPP_WARN_STREAM(
57 getLogger(), "[" << getName() << "] requested index: " << backIndex
58 << ", history size: " << trajectoryHistory_.size());
59 return false;
60 }
61
62 trajectory =
63 this->trajectoryHistory_[this->trajectoryHistory_.size() - 1 - backIndex].trajectory;
64 return true;
65 }
std::vector< TrajectoryHistoryEntry > trajectoryHistory_
virtual std::string getName() const
rclcpp::Logger getLogger() const

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and trajectoryHistory_.

Referenced by getLastTrajectory(), cl_moveit2z::CbExecuteLastTrajectory::onEntry(), cl_moveit2z::CbMoveLastTrajectoryInitialState::onEntry(), and cl_moveit2z::CbUndoLastTrajectory::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getLastTrajectory() [2/4]

bool cl_moveit2z::CpTrajectoryHistory::getLastTrajectory ( int backIndex,
moveit_msgs::msg::RobotTrajectory & trajectory )

◆ getLastTrajectory() [3/4]

bool cl_moveit2z::CpTrajectoryHistory::getLastTrajectory ( moveit_msgs::msg::RobotTrajectory & trajectory)
inline

Definition at line 67 of file cp_trajectory_history.hpp.

68 {
69 return getLastTrajectory(-1, trajectory);
70 }
bool getLastTrajectory(int backIndex, moveit_msgs::msg::RobotTrajectory &trajectory)

References getLastTrajectory().

Here is the call graph for this function:

◆ getLastTrajectory() [4/4]

bool cl_moveit2z::CpTrajectoryHistory::getLastTrajectory ( moveit_msgs::msg::RobotTrajectory & trajectory)

◆ pushTrajectory() [1/2]

void cl_moveit2z::CpTrajectoryHistory::pushTrajectory ( std::string name,
const moveit_msgs::msg::RobotTrajectory & trajectory,
moveit_msgs::msg::MoveItErrorCodes result )
inline

Definition at line 72 of file cp_trajectory_history.hpp.

75 {
76 RCLCPP_INFO_STREAM(
77 getLogger(), "[" << getName() << "] adding a new trajectory to the history ( "
78 << trajectory.joint_trajectory.points.size() << " poses)");
79
80 TrajectoryHistoryEntry entry;
81 this->trajectoryHistory_.push_back(entry);
82
83 auto & last = this->trajectoryHistory_.back();
84 last.trajectory = trajectory;
85 last.result = result;
86 last.name = name;
87 }

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), cl_moveit2z::TrajectoryHistoryEntry::trajectory, and trajectoryHistory_.

Referenced by cl_moveit2z::CbMoveEndEffectorTrajectory::onEntry(), and cl_moveit2z::CpTrajectoryExecutor::recordToHistory().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pushTrajectory() [2/2]

void cl_moveit2z::CpTrajectoryHistory::pushTrajectory ( std::string name,
const moveit_msgs::msg::RobotTrajectory & trajectory,
moveit_msgs::msg::MoveItErrorCodes result )

Member Data Documentation

◆ trajectoryHistory_

std::vector< TrajectoryHistoryEntry > cl_moveit2z::CpTrajectoryHistory::trajectoryHistory_
private

Definition at line 90 of file cp_trajectory_history.hpp.

Referenced by getLastTrajectory(), and pushTrajectory().


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