42 #include <tf2_eigen/tf2_eigen.hpp>
47 #include <moveit_msgs/msg/display_trajectory.hpp>
65 static const rclcpp::Logger
LOGGER =
66 rclcpp::get_logger(
"moveit_move_group_default_capabilities.cartersian_path_service_capability");
75 display_path_ =
context_->moveit_cpp_->getNode()->create_publisher<moveit_msgs::msg::DisplayTrajectory>(
78 cartesian_path_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetCartesianPath>(
80 CARTESIAN_PATH_SERVICE_NAME,
81 [
this](
const std::shared_ptr<rmw_request_id_t>& req_id,
82 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
83 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res) ->
bool {
84 return computeService(req_id, req, res);
88 bool MoveGroupCartesianPathService::computeService(
89 const std::shared_ptr<rmw_request_id_t>& ,
90 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
91 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res)
93 RCLCPP_INFO(LOGGER,
"Received request to compute Cartesian path");
94 context_->planning_scene_monitor_->updateFrameTransforms();
101 std::string link_name = req->link_name;
102 if (link_name.empty() && !jmg->getLinkModelNames().empty())
103 link_name = jmg->getLinkModelNames().back();
106 EigenSTL::vector_Isometry3d
waypoints(req->waypoints.size());
107 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
108 bool no_transform = req->header.frame_id.empty() ||
112 for (std::size_t i = 0; i < req->waypoints.size(); ++i)
115 tf2::fromMsg(req->waypoints[i],
waypoints[i]);
118 geometry_msgs::msg::PoseStamped
p;
119 p.header = req->header;
120 p.pose = req->waypoints[i];
125 RCLCPP_ERROR(LOGGER,
"Error encountered transforming waypoints to frame '%s'", default_frame.c_str());
134 if (req->max_step < std::numeric_limits<double>::epsilon())
136 RCLCPP_ERROR(LOGGER,
"Maximum step to take between consecutive configurations along Cartesian path"
137 "was not specified (this value needs to be > 0)");
138 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
145 std::unique_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
146 std::unique_ptr<kinematic_constraints::KinematicConstraintSet> kset;
149 ls = std::make_unique<planning_scene_monitor::LockedPlanningSceneRO>(
context_->planning_scene_monitor_);
150 kset = std::make_unique<kinematic_constraints::KinematicConstraintSet>((*ls)->getRobotModel());
151 kset->add(req->path_constraints, (*ls)->getTransforms());
153 [
scene = req->avoid_collisions ?
static_cast<const planning_scene::PlanningSceneConstPtr&
>(*ls).get() :
157 const double* joint_group_variable_values) {
158 return isStateValid(
scene, kset, robot_state, joint_group, joint_group_variable_values);
163 "Attempting to follow %u waypoints for link '%s' using a step of %lf m "
164 "and jump threshold %lf (in %s reference frame)",
165 (
unsigned int)
waypoints.size(), link_name.c_str(), req->max_step, req->jump_threshold,
166 global_frame ?
"global" :
"link");
167 std::vector<moveit::core::RobotStatePtr> traj;
174 for (
const moveit::core::RobotStatePtr& traj_state : traj)
175 rt.addSuffixWayPoint(traj_state, 0.0);
182 rt.getRobotTrajectoryMsg(res->solution);
183 RCLCPP_INFO(LOGGER,
"Computed Cartesian path with %u points (followed %lf%% of requested trajectory)",
184 (
unsigned int)traj.size(), res->fraction * 100.0);
185 if (display_computed_paths_ && rt.getWayPointCount() > 0)
187 moveit_msgs::msg::DisplayTrajectory disp;
188 disp.model_id =
context_->planning_scene_monitor_->getRobotModel()->getName();
189 disp.trajectory.resize(1, res->solution);
191 display_path_->publish(disp);
194 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
198 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
201 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
208 #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(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 JumpThreshold &jump_threshold, 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...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
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.
void update(bool force=false)
Update all transforms.
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed,...
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
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.
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
bool satisfied
Whether or not the constraint or constraints were satisfied.
Struct for containing jump_threshold.
Struct for containing max_step for computeCartesianPath.