SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Private Attributes | List of all members
cl_moveit2z::CbUndoLastTrajectory Class Reference

#include <cb_undo_last_trajectory.hpp>

Inheritance diagram for cl_moveit2z::CbUndoLastTrajectory:
Inheritance graph
Collaboration diagram for cl_moveit2z::CbUndoLastTrajectory:
Collaboration graph

Public Member Functions

 CbUndoLastTrajectory ()
 
 CbUndoLastTrajectory (int backIndex)
 
virtual ~CbUndoLastTrajectory ()
 
virtual void onEntry () override
 
virtual void generateTrajectory ()
 
- Public Member Functions inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
 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 >
void onOrthogonalAllocation ()
 
virtual void onExit () override
 
virtual void update () override
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
boost::signals2::connection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
 
- Public Member Functions inherited from smacc2::ISmaccUpdatable
 ISmaccUpdatable ()
 
 ISmaccUpdatable (rclcpp::Duration duration)
 
void executeUpdate (rclcpp::Node::SharedPtr node)
 
void setUpdatePeriod (rclcpp::Duration duration)
 

Private Attributes

int backIndex_ = -1
 
moveit_msgs::msg::RobotTrajectory trajectory
 
moveit_msgs::msg::RobotTrajectory reversed
 

Additional Inherited Members

- Public Attributes inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
std::optional< std::string > group_
 
std::optional< std::string > tipLink_
 
std::optional< boolallowInitialTrajectoryStateJointDiscontinuity_
 
- Protected Member Functions inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory (moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
 
void executeJointSpaceTrajectory (const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
 
virtual void createMarkers ()
 
void getCurrentEndEffectorPose (std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
 
- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 
- Protected Attributes inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
 
ClMoveit2zmovegroupClient_ = nullptr
 
visualization_msgs::msg::MarkerArray beahiorMarkers_
 

Detailed Description

Definition at line 28 of file cb_undo_last_trajectory.hpp.

Constructor & Destructor Documentation

◆ CbUndoLastTrajectory() [1/2]

cl_moveit2z::CbUndoLastTrajectory::CbUndoLastTrajectory ( )

Definition at line 26 of file cb_undo_last_trajectory.cpp.

26{}

◆ CbUndoLastTrajectory() [2/2]

cl_moveit2z::CbUndoLastTrajectory::CbUndoLastTrajectory ( int  backIndex)

Definition at line 28 of file cb_undo_last_trajectory.cpp.

◆ ~CbUndoLastTrajectory()

cl_moveit2z::CbUndoLastTrajectory::~CbUndoLastTrajectory ( )
virtual

Definition at line 30 of file cb_undo_last_trajectory.cpp.

30{}

Member Function Documentation

◆ generateTrajectory()

void cl_moveit2z::CbUndoLastTrajectory::generateTrajectory ( )
virtual

Implements cl_moveit2z::CbMoveEndEffectorTrajectory.

Definition at line 32 of file cb_undo_last_trajectory.cpp.

32{}

◆ onEntry()

void cl_moveit2z::CbUndoLastTrajectory::onEntry ( )
overridevirtual

Reimplemented from cl_moveit2z::CbMoveEndEffectorTrajectory.

Definition at line 34 of file cb_undo_last_trajectory.cpp.

35{
36 CpTrajectoryHistory * trajectoryHistory;
37 this->requiresComponent(trajectoryHistory);
39
40 if (trajectoryHistory->getLastTrajectory(backIndex_, trajectory))
41 {
42 RCLCPP_WARN_STREAM(
43 getLogger(), "[" << getName() << "] reversing last trajectory [" << backIndex_ << "]");
44
45 auto initialTime = trajectory.joint_trajectory.points.back().time_from_start;
46
48
49 std::reverse(reversed.joint_trajectory.points.begin(), reversed.joint_trajectory.points.end());
50
51 for (auto & jp : reversed.joint_trajectory.points)
52 {
53 jp.time_from_start = rclcpp::Duration(initialTime) - rclcpp::Duration(jp.time_from_start);
54 }
55
57 }
58 else
59 {
60 RCLCPP_WARN_STREAM(
61 getLogger(), "[" << getName() << "] could not undo last trajectory, trajectory not found.");
62 }
63}
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
moveit_msgs::msg::RobotTrajectory trajectory
moveit_msgs::msg::RobotTrajectory reversed
virtual rclcpp::Logger getLogger() const
void requiresClient(SmaccClientType *&storage)
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)

References backIndex_, cl_moveit2z::CbMoveEndEffectorTrajectory::executeJointSpaceTrajectory(), cl_moveit2z::CpTrajectoryHistory::getLastTrajectory(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), cl_moveit2z::CbMoveEndEffectorTrajectory::movegroupClient_, smacc2::ISmaccClientBehavior::requiresClient(), smacc2::ISmaccClientBehavior::requiresComponent(), reversed, and trajectory.

Here is the call graph for this function:

Member Data Documentation

◆ backIndex_

int cl_moveit2z::CbUndoLastTrajectory::backIndex_ = -1
private

Definition at line 42 of file cb_undo_last_trajectory.hpp.

Referenced by onEntry().

◆ reversed

moveit_msgs::msg::RobotTrajectory cl_moveit2z::CbUndoLastTrajectory::reversed
private

Definition at line 45 of file cb_undo_last_trajectory.hpp.

Referenced by onEntry().

◆ trajectory

moveit_msgs::msg::RobotTrajectory cl_moveit2z::CbUndoLastTrajectory::trajectory
private

Definition at line 44 of file cb_undo_last_trajectory.hpp.

Referenced by onEntry().


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