SMACC2
cb_move_end_effector_trajectory.hpp
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#pragma once
22
23#include <tf2/transform_datatypes.h>
25#include <moveit_msgs/srv/get_position_ik.hpp>
27#include <visualization_msgs/msg/marker_array.hpp>
28
30{
31template <typename AsyncCB, typename Orthogonal>
32struct EvJointDiscontinuity : sc::event<EvJointDiscontinuity<AsyncCB, Orthogonal>>
33{
34 moveit_msgs::msg::RobotTrajectory trajectory;
35};
36
37template <typename AsyncCB, typename Orthogonal>
38struct EvIncorrectInitialPosition : sc::event<EvIncorrectInitialPosition<AsyncCB, Orthogonal>>
39{
40 moveit_msgs::msg::RobotTrajectory trajectory;
41};
42
44{
45 SUCCESS,
48};
49
50// this is a base behavior to define any kind of parametrized family of trajectories or motions
53{
54public:
55 // std::string tip_link_;
56 std::optional<std::string> group_;
57
58 std::optional<std::string> tipLink_;
59
61
62 CbMoveEndEffectorTrajectory(std::optional<std::string> tipLink = std::nullopt);
63
65 const std::vector<geometry_msgs::msg::PoseStamped> & endEffectorTrajectory,
66 std::optional<std::string> tipLink = std::nullopt);
67
68 template <typename TOrthogonal, typename TSourceObject>
70 {
71 this->initializeROS();
72
73 smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
74
75 postJointDiscontinuityEvent = [this](auto traj) {
77 ev->trajectory = traj;
78 this->postEvent(ev);
79 };
80
81 postIncorrectInitialStateEvent = [this](auto traj) {
83 ev->trajectory = traj;
84 this->postEvent(ev);
85 };
86
88 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] motion execution failed");
90 this->postEvent<EvMoveGroupMotionExecutionFailed<TSourceObject, TOrthogonal>>();
91 };
92 }
93
94 virtual void onEntry() override;
95
96 virtual void onExit() override;
97
98 virtual void update() override;
99
100protected:
102 moveit_msgs::msg::RobotTrajectory & computedJointTrajectory);
103
105 const moveit_msgs::msg::RobotTrajectory & computedJointTrajectory);
106
107 virtual void generateTrajectory() = 0;
108
109 virtual void createMarkers();
110
111 std::vector<geometry_msgs::msg::PoseStamped> endEffectorTrajectory_;
112
114
115 visualization_msgs::msg::MarkerArray beahiorMarkers_;
116
118 std::string globalFrame, tf2::Stamped<tf2::Transform> & currentEndEffectorTransform);
119
120private:
121 void initializeROS();
122
123 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr markersPub_;
124
125 std::atomic<bool> markersInitialized_;
126
127 rclcpp::Client<moveit_msgs::srv::GetPositionIK>::SharedPtr iksrv_;
128
129 std::mutex m_mutex_;
130
131 std::function<void(moveit_msgs::msg::RobotTrajectory &)> postJointDiscontinuityEvent;
132 std::function<void(moveit_msgs::msg::RobotTrajectory &)> postIncorrectInitialStateEvent;
133
134 std::function<void()> postMotionExecutionFailureEvents;
135
136 bool autocleanmarkers = false;
137};
138} // namespace cl_move_group_interface
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postIncorrectInitialStateEvent
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postJointDiscontinuityEvent
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr markersPub_
rclcpp::Client< moveit_msgs::srv::GetPositionIK >::SharedPtr iksrv_
CbMoveEndEffectorTrajectory(std::optional< std::string > tipLink=std::nullopt)
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)