21#include <tf2/transform_datatypes.h>
22#include <tf2_ros/transform_listener.h>
27#include <moveit_msgs/srv/get_position_ik.hpp>
29#include <visualization_msgs/msg/marker_array.hpp>
31using namespace std::chrono_literals;
36: tipLink_(tipLink), markersInitialized_(false)
41 const std::vector<geometry_msgs::msg::PoseStamped> & endEffectorTrajectory,
42 std::optional<std::string> tipLink)
43: tipLink_(tipLink), endEffectorTrajectory_(endEffectorTrajectory), markersInitialized_(false)
53 markersPub_ = nh->create_publisher<visualization_msgs::msg::MarkerArray>(
"trajectory_markers", 1);
54 iksrv_ = nh->create_client<moveit_msgs::srv::GetPositionIK>(
"/compute_ik");
58 moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
60 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] getting current state.. waiting");
68 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] getting joint names");
69 auto currentjointnames =
currentState->getJointModelGroup(groupname)->getActiveJointModelNames();
76 std::vector<double> jointPositions;
77 currentState->copyJointGroupPositions(groupname, jointPositions);
79 std::vector<std::vector<double>> trajectory;
80 std::vector<rclcpp::Duration> trajectoryTimeStamps;
82 trajectory.push_back(jointPositions);
83 trajectoryTimeStamps.push_back(rclcpp::Duration(0
s));
86 rclcpp::Time referenceTime(first.header.stamp);
88 std::vector<int> discontinuityIndexes;
94 auto req = std::make_shared<moveit_msgs::srv::GetPositionIK::Request>();
97 req->ik_request.ik_link_name = *
tipLink_;
98 req->ik_request.robot_state.joint_state.name = currentjointnames;
99 req->ik_request.robot_state.joint_state.position = jointPositions;
101 req->ik_request.group_name = groupname;
102 req->ik_request.avoid_collisions =
true;
105 req->ik_request.pose_stamped = pose;
107 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] IK request: " << k <<
" " << *req);
109 auto resfut =
iksrv_->async_send_request(req);
111 auto status = resfut.wait_for(3
s);
112 if (status == std::future_status::ready)
116 auto & prevtrajpoint = trajectory.back();
119 auto res = resfut.get();
120 std::stringstream ss;
121 for (
size_t j = 0; j < res->solution.joint_state.position.size(); j++)
123 auto & jointname = res->solution.joint_state.name[j];
124 auto it = std::find(currentjointnames.begin(), currentjointnames.end(), jointname);
125 if (it != currentjointnames.end())
127 int index = std::distance(currentjointnames.begin(), it);
128 jointPositions[index] = res->solution.joint_state.position[j];
129 ss << jointname <<
"(" << index <<
"): " << jointPositions[index] << std::endl;
134 size_t jointindex = 0;
135 int discontinuityJointIndex = -1;
136 double discontinuityDeltaJointIndex = -1;
141 !(*allowInitialTrajectoryStateJointDiscontinuity_));
144 for (jointindex = 0; jointindex < jointPositions.size(); jointindex++)
146 deltajoint = jointPositions[jointindex] - prevtrajpoint[jointindex];
148 if (fabs(deltajoint) > 0.3 )
150 discontinuityDeltaJointIndex = deltajoint;
151 discontinuityJointIndex = jointindex;
156 if (ikAttempts > 0 && discontinuityJointIndex != -1)
164 bool discontinuity =
false;
167 discontinuityIndexes.push_back(k);
168 discontinuity =
true;
173 if (discontinuity && discontinuityJointIndex != -1)
176 std::stringstream ss;
178 << currentjointnames[discontinuityJointIndex]
179 <<
" IK discontinuity : " << discontinuityDeltaJointIndex << std::endl
180 <<
"prev joint value: " << prevtrajpoint[discontinuityJointIndex] << std::endl
181 <<
"current joint value: " << jointPositions[discontinuityJointIndex] << std::endl;
184 for (
size_t ji = 0; ji < jointPositions.size(); ji++)
186 ss << currentjointnames[ji] <<
": " << jointPositions[ji] << std::endl;
189 for (
size_t kindex = 0; kindex < trajectory.size(); kindex++)
191 ss <<
"[" << kindex <<
"]: " << trajectory[kindex][discontinuityJointIndex]
197 ss <<
"This is the first posture of the trajectory. Maybe the robot initial posture is "
198 "not coincident to the initial posture of the generated joint trajectory."
202 RCLCPP_ERROR_STREAM(
getLogger(), ss.str());
204 trajectory.push_back(jointPositions);
205 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
206 trajectoryTimeStamps.push_back(durationFromStart);
212 trajectory.push_back(jointPositions);
213 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
214 trajectoryTimeStamps.push_back(durationFromStart);
216 RCLCPP_DEBUG_STREAM(
getLogger(),
"IK solution: " << res->solution.joint_state);
217 RCLCPP_DEBUG_STREAM(
getLogger(),
"trajpoint: " << std::endl << ss.str());
237 computedJointTrajectory.joint_trajectory.joint_names = currentjointnames;
239 for (
auto & p : trajectory)
249 trajectory_msgs::msg::JointTrajectoryPoint jp;
251 jp.time_from_start = trajectoryTimeStamps[i];
252 computedJointTrajectory.joint_trajectory.points.push_back(jp);
256 if (discontinuityIndexes.size())
258 if (discontinuityIndexes[0] == 0)
268 const moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
270 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] Executing joint trajectory");
272 auto executionResult =
275 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
277 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] motion execution succeeded");
292 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] Generating end effector trajectory");
300 <<
"] No points in the trajectory. Skipping behavior.");
308 moveit_msgs::msg::RobotTrajectory computedTrajectory;
310 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] Computing joint space trajectory.");
319 if (!trajectoryGenerationSuccess)
322 getLogger(),
"[" << this->
getName() <<
"] Incorrect trajectory. Posting failure event.");
323 if (trajectoryHistory !=
nullptr)
325 moveit_msgs::msg::MoveItErrorCodes error;
326 error.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
345 if (trajectoryHistory !=
nullptr)
347 moveit_msgs::msg::MoveItErrorCodes error;
348 error.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
362 std::lock_guard<std::mutex> guard(
m_mutex_);
373 std::lock_guard<std::mutex> guard(
m_mutex_);
376 marker.header.stamp =
getNode()->now();
377 marker.action = visualization_msgs::msg::Marker::DELETE;
386 tf2::Transform localdirection;
387 localdirection.setIdentity();
388 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
393 visualization_msgs::msg::Marker marker;
394 marker.header.frame_id = frameid;
395 marker.header.stamp =
getNode()->now();
396 marker.ns =
"trajectory";
398 marker.type = visualization_msgs::msg::Marker::ARROW;
399 marker.action = visualization_msgs::msg::Marker::ADD;
400 marker.scale.x = 0.005;
401 marker.scale.y = 0.01;
402 marker.scale.z = 0.01;
403 marker.color.a = 0.8;
404 marker.color.r = 1.0;
408 geometry_msgs::msg::Point start, end;
413 tf2::Transform basetransform;
414 tf2::fromMsg(pose.pose, basetransform);
417 end.x = localdirection.getOrigin().x();
418 end.y = localdirection.getOrigin().y();
419 end.z = localdirection.getOrigin().z();
421 marker.pose.position = pose.pose.position;
422 marker.pose.orientation = pose.pose.orientation;
423 marker.points.push_back(start);
424 marker.points.push_back(end);
437 std::string globalFrame, tf2::Stamped<tf2::Transform> & currentEndEffectorTransform)
439 tf2_ros::Buffer tfBuffer(
getNode()->get_clock());
440 tf2_ros::TransformListener tfListener(tfBuffer);
450 tfBuffer.lookupTransform(globalFrame, *
tipLink_, rclcpp::Time(0), rclcpp::Duration(10
s)),
451 currentEndEffectorTransform);
459 catch (
const std::exception & e)
461 std::cerr << e.what() << std::endl;
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postIncorrectInitialStateEvent
std::optional< bool > allowInitialTrajectoryStateJointDiscontinuity_
std::optional< std::string > tipLink_
virtual void createMarkers()
virtual void onExit() override
virtual void update() override
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > ¤tEndEffectorTransform)
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postJointDiscontinuityEvent
std::function< void()> postMotionExecutionFailureEvents
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr markersPub_
virtual void onEntry() override
virtual void generateTrajectory()=0
rclcpp::Client< moveit_msgs::srv::GetPositionIK >::SharedPtr iksrv_
visualization_msgs::msg::MarkerArray beahiorMarkers_
std::atomic< bool > markersInitialized_
CbMoveEndEffectorTrajectory(std::optional< std::string > tipLink=std::nullopt)
ClMoveGroup * movegroupClient_
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
void postEventMotionExecutionFailed()
void postEventMotionExecutionSucceded()
void pushTrajectory(std::string name, const moveit_msgs::msg::RobotTrajectory &trajectory, moveit_msgs::msg::MoveItErrorCodes result)
std::string getName() const
virtual rclcpp::Logger getLogger()
virtual rclcpp::Node::SharedPtr getNode()
ISmaccState * currentState
void requiresClient(SmaccClientType *&storage)
void requiresComponent(SmaccComponentType *&storage)
ComputeJointTrajectoryErrorCode
@ INCORRECT_INITIAL_STATE
@ JOINT_TRAJECTORY_DISCONTINUITY
std::string demangleSymbol(const std::string &name)