SMACC
Loading...
Searching...
No Matches
cb_execute_last_trajectory.cpp
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018-2020
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
8
10{
12 {
13 }
14
16 {
17
18 }
19
21 {
23
24 CpTrajectoryHistory *trajectoryHistory;
25 this->requiresComponent(trajectoryHistory);
26
27 // this->generateTrajectory();
28 // endEffectorTrajectory_ =
29
30 // if (this->endEffectorTrajectory_.size() == 0)
31 // {
32 // ROS_WARN_STREAM("[" << smacc::demangleSymbol(typeid(*this).name()) << "] No points in the trajectory. Skipping behavior.");
33 // return;
34 // }
35
36 //this->createMarkers();
37 //markersInitialized_ = true;
38
39 moveit_msgs::RobotTrajectory trajectory;
40
41 if (trajectoryHistory->getLastTrajectory(trajectory))
42 {
43 this->executeJointSpaceTrajectory(trajectory);
44 }
45 }
46
47} // namespace cl_move_group_interface
void executeJointSpaceTrajectory(const moveit_msgs::RobotTrajectory &computedJointTrajectory)
bool getLastTrajectory(int backIndex, moveit_msgs::RobotTrajectory &trajectory)
void requiresComponent(SmaccComponentType *&storage)
void requiresClient(SmaccClientType *&storage)