.. _program_listing_file__tmp_ws_src_SMACC2_smacc2_client_library_move_group_interface_client_include_move_group_interface_client_client_behaviors_cb_move_end_effector_trajectory.hpp: Program Listing for File cb_move_end_effector_trajectory.hpp ============================================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/SMACC2/smacc2_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_end_effector_trajectory.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 RobosoftAI Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. /***************************************************************************************************************** * * Authors: Pablo Inigo Blasco, Brett Aldrich * *****************************************************************************************************************/ #pragma once #include #include #include #include #include namespace cl_move_group_interface { template struct EvJointDiscontinuity : sc::event> { moveit_msgs::msg::RobotTrajectory trajectory; }; template struct EvIncorrectInitialPosition : sc::event> { moveit_msgs::msg::RobotTrajectory trajectory; }; enum class ComputeJointTrajectoryErrorCode { SUCCESS, INCORRECT_INITIAL_STATE, JOINT_TRAJECTORY_DISCONTINUITY }; // this is a base behavior to define any kind of parametrized family of trajectories or motions class CbMoveEndEffectorTrajectory : public smacc2::SmaccAsyncClientBehavior, public smacc2::ISmaccUpdatable { public: // std::string tip_link_; std::optional group_; std::optional tipLink_; std::optional allowInitialTrajectoryStateJointDiscontinuity_; CbMoveEndEffectorTrajectory(std::optional tipLink = std::nullopt); CbMoveEndEffectorTrajectory( const std::vector & endEffectorTrajectory, std::optional tipLink = std::nullopt); template void onOrthogonalAllocation() { this->initializeROS(); smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation(); postJointDiscontinuityEvent = [this](auto traj) { auto ev = new EvJointDiscontinuity(); ev->trajectory = traj; this->postEvent(ev); }; postIncorrectInitialStateEvent = [this](auto traj) { auto ev = new EvIncorrectInitialPosition(); ev->trajectory = traj; this->postEvent(ev); }; postMotionExecutionFailureEvents = [this] { RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] motion execution failed"); movegroupClient_->postEventMotionExecutionFailed(); this->postEvent>(); }; } virtual void onEntry() override; virtual void onExit() override; virtual void update() override; protected: ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory( moveit_msgs::msg::RobotTrajectory & computedJointTrajectory); void executeJointSpaceTrajectory( const moveit_msgs::msg::RobotTrajectory & computedJointTrajectory); virtual void generateTrajectory() = 0; virtual void createMarkers(); std::vector endEffectorTrajectory_; ClMoveGroup * movegroupClient_ = nullptr; visualization_msgs::msg::MarkerArray beahiorMarkers_; void getCurrentEndEffectorPose( std::string globalFrame, tf2::Stamped & currentEndEffectorTransform); private: void initializeROS(); rclcpp::Publisher::SharedPtr markersPub_; std::atomic markersInitialized_; rclcpp::Client::SharedPtr iksrv_; std::mutex m_mutex_; std::function postJointDiscontinuityEvent; std::function postIncorrectInitialStateEvent; std::function postMotionExecutionFailureEvents; bool autocleanmarkers = false; }; } // namespace cl_move_group_interface