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>
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);
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);
86 const std::map<std::string, double>& joint_state, Eigen::Isometry3d& pose);
89 const std::vector<std::string>& joint_names,
const std::vector<double>& joint_positions,
90 Eigen::Isometry3d& pose);
106 const std::map<std::string, double>& velocity_last,
107 const std::map<std::string, double>& position_current,
double duration_last,
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);
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);
161 const robot_trajectory::RobotTrajectoryPtr& second_trajectory,
double EPSILON,
162 double& sampling_time);
177 const std::string& joint_group_name,
double epsilon);
200 const robot_trajectory::RobotTrajectoryPtr& traj,
bool inverseOrder,
203bool intersectionFound(
const Eigen::Vector3d& p_center,
const Eigen::Vector3d& p_current,
const Eigen::Vector3d& p_next,
230 const geometry_msgs::msg::Quaternion& orientation,
231 const geometry_msgs::msg::Vector3& offset);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 ¢er_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.