SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
move_group_interface_client
src
move_group_interface_client
client_behaviors
cb_undo_last_trajectory.cpp
Go to the documentation of this file.
1
// Copyright 2021 RobosoftAI Inc.
2
//
3
// Licensed under the Apache License, Version 2.0 (the "License");
4
// you may not use this file except in compliance with the License.
5
// You may obtain a copy of the License at
6
//
7
// http://www.apache.org/licenses/LICENSE-2.0
8
//
9
// Unless required by applicable law or agreed to in writing, software
10
// distributed under the License is distributed on an "AS IS" BASIS,
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
// See the License for the specific language governing permissions and
13
// limitations under the License.
14
15
/*****************************************************************************************************************
16
*
17
* Authors: Pablo Inigo Blasco, Brett Aldrich
18
*
19
******************************************************************************************************************/
20
21
#include <
move_group_interface_client/client_behaviors/cb_undo_last_trajectory.hpp
>
22
#include <
move_group_interface_client/components/cp_trajectory_history.hpp
>
23
24
namespace
cl_move_group_interface
25
{
26
CbUndoLastTrajectory::CbUndoLastTrajectory
() {}
27
28
CbUndoLastTrajectory::CbUndoLastTrajectory
(
int
backIndex) : backIndex_(backIndex) {}
29
30
CbUndoLastTrajectory::~CbUndoLastTrajectory
() {}
31
32
void
CbUndoLastTrajectory::generateTrajectory
() {}
33
34
void
CbUndoLastTrajectory::onEntry
()
35
{
36
CpTrajectoryHistory
* trajectoryHistory;
37
this->
requiresComponent
(trajectoryHistory);
38
this->
requiresClient
(
movegroupClient_
);
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
47
reversed
=
trajectory
;
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
56
this->
executeJointSpaceTrajectory
(
reversed
);
57
}
58
else
59
{
60
RCLCPP_WARN_STREAM(
61
getLogger
(),
"["
<<
getName
() <<
"] could not undo last trajectory, trajectory not found."
);
62
}
63
}
64
65
}
// namespace cl_move_group_interface
cb_undo_last_trajectory.hpp
cl_move_group_interface::CbMoveEndEffectorTrajectory::movegroupClient_
ClMoveGroup * movegroupClient_
Definition:
cb_move_end_effector_trajectory.hpp:116
cl_move_group_interface::CbMoveEndEffectorTrajectory::executeJointSpaceTrajectory
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
Definition:
cb_move_end_effector_trajectory.cpp:267
cl_move_group_interface::CbUndoLastTrajectory::backIndex_
int backIndex_
Definition:
cb_undo_last_trajectory.hpp:42
cl_move_group_interface::CbUndoLastTrajectory::trajectory
moveit_msgs::msg::RobotTrajectory trajectory
Definition:
cb_undo_last_trajectory.hpp:44
cl_move_group_interface::CbUndoLastTrajectory::CbUndoLastTrajectory
CbUndoLastTrajectory()
Definition:
cb_undo_last_trajectory.cpp:26
cl_move_group_interface::CbUndoLastTrajectory::onEntry
virtual void onEntry() override
Definition:
cb_undo_last_trajectory.cpp:34
cl_move_group_interface::CbUndoLastTrajectory::reversed
moveit_msgs::msg::RobotTrajectory reversed
Definition:
cb_undo_last_trajectory.hpp:45
cl_move_group_interface::CbUndoLastTrajectory::~CbUndoLastTrajectory
virtual ~CbUndoLastTrajectory()
Definition:
cb_undo_last_trajectory.cpp:30
cl_move_group_interface::CbUndoLastTrajectory::generateTrajectory
virtual void generateTrajectory()
Definition:
cb_undo_last_trajectory.cpp:32
cl_move_group_interface::CpTrajectoryHistory
Definition:
cp_trajectory_history.hpp:38
cl_move_group_interface::CpTrajectoryHistory::getLastTrajectory
bool getLastTrajectory(int backIndex, moveit_msgs::msg::RobotTrajectory &trajectory)
Definition:
cp_trajectory_history.cpp:25
smacc2::ISmaccClientBehavior::getName
std::string getName() const
Definition:
smacc_client_behavior_base.cpp:36
smacc2::ISmaccClientBehavior::getLogger
virtual rclcpp::Logger getLogger() const
Definition:
smacc_client_behavior_base.cpp:43
smacc2::ISmaccClientBehavior::requiresClient
void requiresClient(SmaccClientType *&storage)
Definition:
smacc_client_behavior_impl.hpp:67
smacc2::ISmaccClientBehavior::requiresComponent
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
Definition:
smacc_client_behavior_impl.hpp:73
cp_trajectory_history.hpp
cl_move_group_interface
Definition:
cl_movegroup.hpp:35
Generated by
1.9.5