moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
cartesian_path_service_capability.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
42#include <tf2_eigen/tf2_eigen.hpp>
47#include <moveit_msgs/msg/display_trajectory.hpp>
50
52
53namespace
54{
55
57const std::string DISPLAY_PATH_TOPIC = std::string("display_planned_path");
58
59bool isStateValid(const planning_scene::PlanningScene* planning_scene,
61 const moveit::core::JointModelGroup* group, const double* ik_solution)
62{
63 state->setJointGroupPositions(group, ik_solution);
64 state->update();
65 return (!planning_scene || !planning_scene->isStateColliding(*state, group->getName())) &&
66 (!constraint_set || constraint_set->decide(*state).satisfied);
67}
68
69rclcpp::Logger getLogger()
70{
71 return moveit::getLogger("moveit.ros.move_group.cartesian_path_service_capability");
72}
73} // namespace
74
75namespace move_group
76{
78 : MoveGroupCapability("CartesianPathService"), display_computed_paths_(true)
79{
80}
81
83{
84 display_path_ =
85 context_->moveit_cpp_->getNode()->create_publisher<moveit_msgs::msg::DisplayTrajectory>(DISPLAY_PATH_TOPIC, 10);
86
87 cartesian_path_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetCartesianPath>(
88
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);
94 });
95}
96
97bool MoveGroupCartesianPathService::computeService(
98 const std::shared_ptr<rmw_request_id_t>& /* unused */,
99 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
100 const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res)
101{
102 RCLCPP_INFO(getLogger(), "Received request to compute Cartesian path");
103 context_->planning_scene_monitor_->updateFrameTransforms();
104
105 moveit::core::RobotState start_state =
106 planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
107 moveit::core::robotStateMsgToRobotState(req->start_state, start_state);
108 if (const moveit::core::JointModelGroup* jmg = start_state.getJointModelGroup(req->group_name))
109 {
110 std::string link_name = req->link_name;
111 if (link_name.empty() && !jmg->getLinkModelNames().empty())
112 link_name = jmg->getLinkModelNames().back();
113
114 bool ok = true;
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() ||
118 moveit::core::Transforms::sameFrame(req->header.frame_id, default_frame) ||
119 moveit::core::Transforms::sameFrame(req->header.frame_id, link_name);
120
121 for (std::size_t i = 0; i < req->waypoints.size(); ++i)
122 {
123 if (no_transform)
124 {
125 tf2::fromMsg(req->waypoints[i], waypoints[i]);
126 }
127 else
128 {
129 geometry_msgs::msg::PoseStamped p;
130 p.header = req->header;
131 p.pose = req->waypoints[i];
132 if (performTransform(p, default_frame))
133 {
134 tf2::fromMsg(p.pose, waypoints[i]);
135 }
136 else
137 {
138 RCLCPP_ERROR(getLogger(), "Error encountered transforming waypoints to frame '%s'", default_frame.c_str());
139 ok = false;
140 break;
141 }
142 }
143 }
144
145 if (ok)
146 {
147 if (req->max_step < std::numeric_limits<double>::epsilon())
148 {
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;
152 }
153 else
154 {
155 if (!waypoints.empty())
156 {
158 std::unique_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
159 std::unique_ptr<kinematic_constraints::KinematicConstraintSet> kset;
160 if (req->avoid_collisions || !moveit::core::isEmpty(req->path_constraints))
161 {
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());
165 constraint_fn =
166 [scene = req->avoid_collisions ? static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get() :
167 nullptr,
168 kset = kset->empty() ? nullptr : kset.get()](moveit::core::RobotState* robot_state,
169 const moveit::core::JointModelGroup* joint_group,
170 const double* joint_group_variable_values) {
171 return isStateValid(scene, kset, robot_state, joint_group, joint_group_variable_values);
172 };
173 }
174 bool global_frame = !moveit::core::Transforms::sameFrame(link_name, req->header.frame_id);
175 RCLCPP_INFO(getLogger(),
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)
182 {
183 jump_threshold = moveit::core::JumpThreshold::relative(req->jump_threshold);
184 }
185 std::vector<moveit::core::RobotStatePtr> traj;
187 &start_state, jmg, traj, start_state.getLinkModel(link_name), waypoints, global_frame,
188 moveit::core::MaxEEFStep(req->max_step), moveit::core::CartesianPrecision{}, constraint_fn);
189 moveit::core::robotStateToRobotStateMsg(start_state, res->start_state);
190
191 robot_trajectory::RobotTrajectory rt(context_->planning_scene_monitor_->getRobotModel(), req->group_name);
192 for (const moveit::core::RobotStatePtr& traj_state : traj)
193 rt.addSuffixWayPoint(traj_state, 0.0);
194
195 // time trajectory
196 // \todo optionally compute timing to move the eef with constant speed
198 time_param.computeTimeStamps(rt, req->max_velocity_scaling_factor, req->max_acceleration_scaling_factor);
199
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)
204 {
205 moveit_msgs::msg::DisplayTrajectory disp;
206 disp.model_id = context_->planning_scene_monitor_->getRobotModel()->getName();
207 disp.trajectory.resize(1, res->solution);
208 moveit::core::robotStateToRobotStateMsg(rt.getFirstWayPoint(), disp.trajectory_start);
209 display_path_->publish(disp);
210 }
211 }
212 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
213 }
214 }
215 else
216 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
217 }
218 else
219 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
220
221 return true;
222}
223
224} // namespace move_group
225
226#include <pluginlib/class_list_macros.hpp>
227
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
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.
Definition robot_state.h:90
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.
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
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_)....
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_...
Definition robot_state.h:70
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.
Definition logger.cpp:79
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.