42#include <tf2_eigen/tf2_eigen.hpp>
47#include <moveit_msgs/msg/display_trajectory.hpp>
57const std::string DISPLAY_PATH_TOPIC = std::string(
"display_planned_path");
71 return moveit::getLogger(
"moveit.ros.move_group.cartesian_path_service_capability");
85 context_->moveit_cpp_->getNode()->create_publisher<moveit_msgs::msg::DisplayTrajectory>(DISPLAY_PATH_TOPIC, 10);
87 cartesian_path_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetCartesianPath>(
89 CARTESIAN_PATH_SERVICE_NAME,
90 [
this](
const std::shared_ptr<rmw_request_id_t>& req_id,
91 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
92 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res) ->
bool {
93 return computeService(req_id, req, res);
97bool MoveGroupCartesianPathService::computeService(
98 const std::shared_ptr<rmw_request_id_t>& ,
99 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
100 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res)
102 RCLCPP_INFO(getLogger(),
"Received request to compute Cartesian path");
103 context_->planning_scene_monitor_->updateFrameTransforms();
110 std::string link_name = req->link_name;
111 if (link_name.empty() && !jmg->getLinkModelNames().empty())
112 link_name = jmg->getLinkModelNames().back();
115 EigenSTL::vector_Isometry3d waypoints(req->waypoints.size());
116 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
117 bool no_transform = req->header.frame_id.empty() ||
121 for (std::size_t i = 0; i < req->waypoints.size(); ++i)
125 tf2::fromMsg(req->waypoints[i], waypoints[i]);
129 geometry_msgs::msg::PoseStamped p;
130 p.header = req->header;
131 p.pose = req->waypoints[i];
134 tf2::fromMsg(p.pose, waypoints[i]);
138 RCLCPP_ERROR(
getLogger(),
"Error encountered transforming waypoints to frame '%s'", default_frame.c_str());
147 if (req->max_step < std::numeric_limits<double>::epsilon())
149 RCLCPP_ERROR(
getLogger(),
"Maximum step to take between consecutive configurations along Cartesian path"
150 "was not specified (this value needs to be > 0)");
151 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
155 if (!waypoints.empty())
158 std::unique_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
159 std::unique_ptr<kinematic_constraints::KinematicConstraintSet> kset;
162 ls = std::make_unique<planning_scene_monitor::LockedPlanningSceneRO>(
context_->planning_scene_monitor_);
163 kset = std::make_unique<kinematic_constraints::KinematicConstraintSet>((*ls)->getRobotModel());
164 kset->add(req->path_constraints, (*ls)->getTransforms());
166 [scene = req->avoid_collisions ?
static_cast<const planning_scene::PlanningSceneConstPtr&
>(*ls).get() :
170 const double* joint_group_variable_values) {
171 return isStateValid(scene, kset, robot_state, joint_group, joint_group_variable_values);
176 "Attempting to follow %u waypoints for link '%s' using a step of %lf m "
177 "and jump threshold %lf (in %s reference frame)",
178 static_cast<unsigned int>(waypoints.size()), link_name.c_str(), req->max_step,
179 req->jump_threshold, global_frame ?
"global" :
"link");
181 if (req->jump_threshold > 0.0)
185 std::vector<moveit::core::RobotStatePtr> traj;
187 &start_state, jmg, traj, start_state.
getLinkModel(link_name), waypoints, global_frame,
192 for (
const moveit::core::RobotStatePtr& traj_state : traj)
193 rt.addSuffixWayPoint(traj_state, 0.0);
198 time_param.
computeTimeStamps(rt, req->max_velocity_scaling_factor, req->max_acceleration_scaling_factor);
200 rt.getRobotTrajectoryMsg(res->solution);
201 RCLCPP_INFO(
getLogger(),
"Computed Cartesian path with %u points (followed %lf%% of requested trajectory)",
202 static_cast<unsigned int>(traj.size()), res->fraction * 100.0);
203 if (display_computed_paths_ && rt.getWayPointCount() > 0)
205 moveit_msgs::msg::DisplayTrajectory disp;
206 disp.model_id =
context_->planning_scene_monitor_->getRobotModel()->getName();
207 disp.trajectory.resize(1, res->solution);
209 display_path_->publish(disp);
212 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
216 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
219 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
226#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
A class that contains many different constraints, and can check RobotState *versus the full set....
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
MoveGroupContextPtr context_
MoveGroupCartesianPathService()
void initialize() override
static Distance computeCartesianPath(const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
const std::string & getName() const
Get the name of the joint group.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
void update(bool force=false)
Update all transforms.
This class maintains the representation of the environment as seen by a planning instance....
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
rclcpp::Logger getLogger()
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
This namespace includes the central class for representing planning contexts.
bool satisfied
Whether or not the constraint or constraints were satisfied.
Struct with options for defining joint-space jump thresholds.
static JumpThreshold relative(double relative_factor)
Detect joint-space jumps relative to the average joint-space displacement along the path.
static JumpThreshold disabled()
Do not define any jump threshold, i.e., disable joint-space jump detection.
Struct for containing max_step for computeCartesianPath.