moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
trajectory_functions.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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#pragma once
36
37#include <Eigen/Geometry>
38#include <kdl/trajectory.hpp>
42#include <tf2/transform_datatypes.h>
43#include <trajectory_msgs/msg/multi_dof_joint_trajectory.hpp>
45
49
51{
67bool computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
68 const std::string& link_name, const Eigen::Isometry3d& pose, const std::string& frame_id,
69 const std::map<std::string, double>& seed, std::map<std::string, double>& solution,
70 bool check_self_collision = true, const double timeout = 0.0);
71
72bool computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
73 const std::string& link_name, const geometry_msgs::msg::Pose& pose, const std::string& frame_id,
74 const std::map<std::string, double>& seed, std::map<std::string, double>& solution,
75 bool check_self_collision = true, const double timeout = 0.0);
76
85bool computeLinkFK(moveit::core::RobotState& robot_state, const std::string& link_name,
86 const std::map<std::string, double>& joint_state, Eigen::Isometry3d& pose);
87
88bool computeLinkFK(moveit::core::RobotState& robot_state, const std::string& link_name,
89 const std::vector<std::string>& joint_names, const std::vector<double>& joint_positions,
90 Eigen::Isometry3d& pose);
91
105bool verifySampleJointLimits(const std::map<std::string, double>& position_last,
106 const std::map<std::string, double>& velocity_last,
107 const std::map<std::string, double>& position_current, double duration_last,
108 double duration_current, const JointLimitsContainer& joint_limits);
109
127bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr& scene,
128 const JointLimitsContainer& joint_limits, const KDL::Trajectory& trajectory,
129 const std::string& group_name, const std::string& link_name,
130 const std::map<std::string, double>& initial_joint_position, double sampling_time,
131 trajectory_msgs::msg::JointTrajectory& joint_trajectory,
132 moveit_msgs::msg::MoveItErrorCodes& error_code, bool check_self_collision = false);
133
144bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr& scene,
147 const std::string& group_name, const std::string& link_name,
148 const std::map<std::string, double>& initial_joint_position,
149 const std::map<std::string, double>& initial_joint_velocity,
150 trajectory_msgs::msg::JointTrajectory& joint_trajectory,
151 moveit_msgs::msg::MoveItErrorCodes& error_code, bool check_self_collision = false);
152
160bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr& first_trajectory,
161 const robot_trajectory::RobotTrajectoryPtr& second_trajectory, double EPSILON,
162 double& sampling_time);
163
177 const std::string& joint_group_name, double epsilon);
178
186bool isRobotStateStationary(const moveit::core::RobotState& state, const std::string& group, double EPSILON);
187
199bool linearSearchIntersectionPoint(const std::string& link_name, const Eigen::Vector3d& center_position, const double r,
200 const robot_trajectory::RobotTrajectoryPtr& traj, bool inverseOrder,
201 std::size_t& index);
202
203bool intersectionFound(const Eigen::Vector3d& p_center, const Eigen::Vector3d& p_current, const Eigen::Vector3d& p_next,
204 double r);
205
216bool isStateColliding(const planning_scene::PlanningSceneConstPtr& scene, moveit::core::RobotState* state,
217 const moveit::core::JointModelGroup* const group, const double* const ik_solution);
218} // namespace pilz_industrial_motion_planner
219
220void normalizeQuaternion(geometry_msgs::msg::Quaternion& quat);
221
229Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point& position,
230 const geometry_msgs::msg::Quaternion& orientation,
231 const geometry_msgs::msg::Vector3& offset);
232
238Eigen::Isometry3d getConstraintPose(const moveit_msgs::msg::Constraints& goal);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
bool computeLinkFK(moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at a given robot state
bool linearSearchIntersectionPoint(const std::string &link_name, const Eigen::Vector3d &center_position, const double r, const robot_trajectory::RobotTrajectoryPtr &traj, bool inverseOrder, std::size_t &index)
Performs a linear search for the intersection point of the trajectory with the blending radius.
bool isStateColliding(const planning_scene::PlanningSceneConstPtr &scene, moveit::core::RobotState *state, const moveit::core::JointModelGroup *const group, const double *const ik_solution)
Checks if current robot state is in self collision.
bool isRobotStateStationary(const moveit::core::RobotState &state, const std::string &group, double EPSILON)
check if the robot state have zero velocity/acceleration
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
Determines the sampling time and checks that both trajectroies use the same sampling time.
bool intersectionFound(const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, double r)
bool verifySampleJointLimits(const std::map< std::string, double > &position_last, const std::map< std::string, double > &velocity_last, const std::map< std::string, double > &position_current, double duration_last, double duration_current, const JointLimitsContainer &joint_limits)
verify the velocity/acceleration limits of current sample (based on backward difference computation) ...
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, double sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
bool computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
compute the inverse kinematics of a given pose, also check robot self collision
bool isRobotStateEqual(const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const std::string &joint_group_name, double epsilon)
Check if the two robot states have the same joint position/velocity/acceleration.
void normalizeQuaternion(geometry_msgs::msg::Quaternion &quat)
Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point &position, const geometry_msgs::msg::Quaternion &orientation, const geometry_msgs::msg::Vector3 &offset)
Adapt goal pose, defined by position+orientation, to consider offset.