Program Listing for File trajectory_functions.h
↰ Return to documentation for file (include/pilz_industrial_motion_planner/trajectory_functions.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 Pilz GmbH & Co. KG
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Pilz GmbH & Co. KG nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#pragma once
#include <Eigen/Geometry>
#include <kdl/trajectory.hpp>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <tf2/transform_datatypes.h>
#include <trajectory_msgs/msg/multi_dof_joint_trajectory.hpp>
#include <moveit/planning_scene/planning_scene.h>
#include <pilz_industrial_motion_planner/cartesian_trajectory.h>
#include <pilz_industrial_motion_planner/limits_container.h>
namespace pilz_industrial_motion_planner
{
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);
bool computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
const std::string& link_name, const geometry_msgs::msg::Pose& 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);
bool computeLinkFK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& link_name,
const std::map<std::string, double>& joint_state, Eigen::Isometry3d& pose);
bool computeLinkFK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& link_name,
const std::vector<std::string>& joint_names, const std::vector<double>& joint_positions,
Eigen::Isometry3d& pose);
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);
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);
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr& scene,
const JointLimitsContainer& joint_limits,
const pilz_industrial_motion_planner::CartesianTrajectory& trajectory,
const std::string& group_name, const std::string& link_name,
const std::map<std::string, double>& initial_joint_position,
const std::map<std::string, double>& initial_joint_velocity,
trajectory_msgs::msg::JointTrajectory& joint_trajectory,
moveit_msgs::msg::MoveItErrorCodes& error_code, bool check_self_collision = false);
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr& first_trajectory,
const robot_trajectory::RobotTrajectoryPtr& second_trajectory, double EPSILON,
double& sampling_time);
bool isRobotStateEqual(const moveit::core::RobotState& state1, const moveit::core::RobotState& state2,
const std::string& joint_group_name, double epsilon);
bool isRobotStateStationary(const moveit::core::RobotState& state, const std::string& group, double EPSILON);
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);
bool intersectionFound(const Eigen::Vector3d& p_center, const Eigen::Vector3d& p_current, const Eigen::Vector3d& p_next,
double r);
bool isStateColliding(const bool test_for_self_collision, const planning_scene::PlanningSceneConstPtr& scene,
moveit::core::RobotState* state, const moveit::core::JointModelGroup* const group,
const double* const ik_solution);
} // namespace pilz_industrial_motion_planner
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);
Eigen::Isometry3d getConstraintPose(const moveit_msgs::msg::Constraints& goal);