8#include <moveit_msgs/GetPositionIK.h>
9#include <visualization_msgs/MarkerArray.h>
10#include <tf/transform_datatypes.h>
12#include <tf/transform_listener.h>
17 : tipLink_(tipLink), markersInitialized_(false)
23 : endEffectorTrajectory_(endEffectorTrajectory), tipLink_(tipLink), markersInitialized_(false)
32 markersPub_ = nh.advertise<visualization_msgs::MarkerArray>(
"trajectory_markers", 1);
33 iksrv_ = nh.serviceClient<moveit_msgs::GetPositionIK>(
"/compute_ik");
43 auto currentjointnames =
currentState->getJointModelGroup(groupname)->getActiveJointModelNames();
50 std::vector<double> jointPositions;
51 currentState->copyJointGroupPositions(groupname, jointPositions);
53 std::vector<std::vector<double>> trajectory;
54 std::vector<ros::Duration> trajectoryTimeStamps;
56 trajectory.push_back(jointPositions);
57 trajectoryTimeStamps.push_back(ros::Duration(0));
60 ros::Time referenceTime = first.header.stamp;
62 std::vector<int> discontinuityIndexes;
68 moveit_msgs::GetPositionIKRequest req;
69 req.ik_request.attempts = 20;
71 req.ik_request.ik_link_name = *
tipLink_;
72 req.ik_request.robot_state.joint_state.name = currentjointnames;
73 req.ik_request.robot_state.joint_state.position = jointPositions;
75 req.ik_request.group_name = groupname;
76 req.ik_request.avoid_collisions =
true;
78 moveit_msgs::GetPositionIKResponse res;
81 req.ik_request.pose_stamped = pose;
83 ROS_DEBUG_STREAM(
"IK request: " << req);
86 auto &prevtrajpoint = trajectory.back();
90 for (
int j = 0; j < res.solution.joint_state.position.size(); j++)
92 auto &jointname = res.solution.joint_state.name[j];
93 auto it = std::find(currentjointnames.begin(), currentjointnames.end(), jointname);
94 if (it != currentjointnames.end())
96 int index = std::distance(currentjointnames.begin(), it);
97 jointPositions[index] = res.solution.joint_state.position[j];
98 ss << jointname <<
"(" << index <<
"): " << jointPositions[index] << std::endl;
104 int discontinuityJointIndex = -1;
105 double discontinuityDeltaJointIndex = -1;
111 for (jointindex = 0; jointindex < jointPositions.size(); jointindex++)
113 deltajoint = jointPositions[jointindex] - prevtrajpoint[jointindex];
115 if (fabs(deltajoint) > 0.3 )
117 discontinuityDeltaJointIndex = deltajoint;
118 discontinuityJointIndex = jointindex;
123 if (ikAttempts > 0 && discontinuityJointIndex != -1)
131 bool discontinuity =
false;
134 discontinuityIndexes.push_back(k);
135 discontinuity =
true;
140 if (discontinuity && discontinuityJointIndex != -1)
143 std::stringstream ss;
144 ss <<
"Traj[" << k <<
"/" <<
endEffectorTrajectory_.size() <<
"] " << currentjointnames[discontinuityJointIndex] <<
" IK discontinuity : " << discontinuityDeltaJointIndex << std::endl
145 <<
"prev joint value: " << prevtrajpoint[discontinuityJointIndex] << std::endl
146 <<
"current joint value: " << jointPositions[discontinuityJointIndex] << std::endl;
149 for (
int ji = 0; ji < jointPositions.size(); ji++)
151 ss << currentjointnames[ji] <<
": " << jointPositions[ji] << std::endl;
154 for (
int kindex = 0; kindex < trajectory.size(); kindex++)
156 ss <<
"[" << kindex <<
"]: " << trajectory[kindex][discontinuityJointIndex] << std::endl;
161 ss <<
"This is the first posture of the trajectory. Maybe the robot initial posture is not coincident to the initial posture of the generated joint trajectory." << std::endl;
164 ROS_ERROR_STREAM(ss.str());
166 trajectory.push_back(jointPositions);
167 ros::Duration durationFromStart = pose.header.stamp - referenceTime;
168 trajectoryTimeStamps.push_back(durationFromStart);
174 trajectory.push_back(jointPositions);
175 ros::Duration durationFromStart = pose.header.stamp - referenceTime;
176 trajectoryTimeStamps.push_back(durationFromStart);
178 ROS_DEBUG_STREAM(
"IK solution: " << res.solution.joint_state);
179 ROS_DEBUG_STREAM(
"trajpoint: " << std::endl
186 ROS_ERROR(
"[CbMoveEndEffectorTrajectory] wrong IK call");
189 ROS_WARN_STREAM(
"-----");
202 computedJointTrajectory.joint_trajectory.joint_names = currentjointnames;
204 for (
auto &p : trajectory)
212 trajectory_msgs::JointTrajectoryPoint jp;
214 jp.time_from_start = trajectoryTimeStamps[i];
215 computedJointTrajectory.joint_trajectory.points.push_back(jp);
219 if (discontinuityIndexes.size())
221 if (discontinuityIndexes[0] == 0)
232 ROS_INFO_STREAM(
"[" << this->
getName() <<
"] Executing joint trajectory");
236 if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)
238 ROS_INFO_STREAM(
"[" << this->
getName() <<
"] motion execution succeeded");
257 ROS_WARN_STREAM(
"[" <<
smacc::demangleSymbol(
typeid(*this).name()) <<
"] No points in the trajectory. Skipping behavior.");
264 moveit_msgs::RobotTrajectory computedTrajectory;
273 if (!trajectoryGenerationSuccess)
275 ROS_INFO_STREAM(
"[" << this->
getName() <<
"] Incorrect trajectory. Posting failure event.");
276 if (trajectoryHistory !=
nullptr)
278 moveit_msgs::MoveItErrorCodes error;
279 error.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
298 if (trajectoryHistory !=
nullptr)
300 moveit_msgs::MoveItErrorCodes error;
301 error.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
315 std::lock_guard<std::mutex> guard(
m_mutex_);
326 std::lock_guard<std::mutex> guard(
m_mutex_);
329 marker.header.stamp = ros::Time::now();
330 marker.action = visualization_msgs::Marker::DELETE;
339 tf::Transform localdirection;
340 localdirection.setIdentity();
341 localdirection.setOrigin(tf::Vector3(0.05, 0, 0));
346 visualization_msgs::Marker marker;
347 marker.header.frame_id = frameid;
348 marker.header.stamp = ros::Time::now();
349 marker.ns =
"trajectory";
351 marker.type = visualization_msgs::Marker::ARROW;
352 marker.action = visualization_msgs::Marker::ADD;
353 marker.scale.x = 0.005;
354 marker.scale.y = 0.01;
355 marker.scale.z = 0.01;
356 marker.color.a = 0.8;
357 marker.color.r = 1.0;
361 geometry_msgs::Point start, end;
366 tf::Transform basetransform;
367 tf::poseMsgToTF(pose.pose, basetransform);
368 tf::Transform endarrow = localdirection * basetransform;
370 end.x = localdirection.getOrigin().x();
371 end.y = localdirection.getOrigin().y();
372 end.z = localdirection.getOrigin().z();
374 marker.pose.position = pose.pose.position;
375 marker.pose.orientation = pose.pose.orientation;
376 marker.points.push_back(start);
377 marker.points.push_back(end);
391 tf::TransformListener tfListener;
400 tfListener.waitForTransform(globalFrame, *
tipLink_, ros::Time(0), ros::Duration(10));
401 tfListener.lookupTransform(globalFrame, *
tipLink_, ros::Time(0), currentEndEffectorTransform);
407 catch (
const std::exception &e)
409 std::cerr << e.what() <<
'\n';
boost::optional< bool > allowInitialTrajectoryStateJointDiscontinuity_
boost::optional< std::string > tipLink_
std::function< void(moveit_msgs::RobotTrajectory &)> postJointDiscontinuityEvent
void executeJointSpaceTrajectory(const moveit_msgs::RobotTrajectory &computedJointTrajectory)
virtual void createMarkers()
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::RobotTrajectory &computedJointTrajectory)
virtual void onExit() override
void getCurrentEndEffectorPose(std::string globalFrame, tf::StampedTransform ¤tEndEffectorTransform)
virtual void update() override
std::function< void(moveit_msgs::RobotTrajectory &)> postIncorrectInitialStateEvent
std::function< void()> postMotionExecutionFailureEvents
visualization_msgs::MarkerArray beahiorMarkers_
ros::ServiceClient iksrv_
ros::Publisher markersPub_
virtual void onEntry() override
std::atomic< bool > markersInitialized_
std::vector< geometry_msgs::PoseStamped > endEffectorTrajectory_
ClMoveGroup * movegroupClient_
virtual void generateTrajectory()
CbMoveEndEffectorTrajectory(std::string tipLink="")
void postEventMotionExecutionFailed()
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
void postEventMotionExecutionSucceded()
void pushTrajectory(std::string name, const moveit_msgs::RobotTrajectory &trajectory, moveit_msgs::MoveItErrorCodes result)
std::string getName() const
void requiresComponent(SmaccComponentType *&storage)
void requiresClient(SmaccClientType *&storage)
ISmaccState * currentState
ComputeJointTrajectoryErrorCode
@ INCORRECT_INITIAL_STATE
@ JOINT_TRAJECTORY_DISCONTINUITY
std::string demangleSymbol()