moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#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>
#include <pilz_industrial_motion_planner/trajectory_generation_exceptions.h>
Go to the source code of this file.
Namespaces | |
pilz_industrial_motion_planner | |
Functions | |
bool | pilz_industrial_motion_planner::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 More... | |
bool | pilz_industrial_motion_planner::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 | pilz_industrial_motion_planner::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 More... | |
bool | pilz_industrial_motion_planner::computeLinkFK (moveit::core::RobotState &robot_state, const std::string &link_name, const std::vector< std::string > &joint_names, const std::vector< double > &joint_positions, Eigen::Isometry3d &pose) |
bool | pilz_industrial_motion_planner::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) v(k) = [x(k) - x(k-1)]/[t(k) - t(k-1)] a(k) = [v(k) - v(k-1)]/[t(k) - t(k-2)]*2 More... | |
bool | pilz_industrial_motion_planner::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, const 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. More... | |
bool | pilz_industrial_motion_planner::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) |
Generate joint trajectory from a MultiDOFJointTrajectory. More... | |
bool | pilz_industrial_motion_planner::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. More... | |
bool | pilz_industrial_motion_planner::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. More... | |
bool | pilz_industrial_motion_planner::isRobotStateStationary (const moveit::core::RobotState &state, const std::string &group, double EPSILON) |
check if the robot state have zero velocity/acceleration More... | |
bool | pilz_industrial_motion_planner::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. More... | |
bool | pilz_industrial_motion_planner::intersectionFound (const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, const double &r) |
bool | pilz_industrial_motion_planner::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. More... | |
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. More... | |
Eigen::Isometry3d | getConstraintPose (const moveit_msgs::msg::Constraints &goal) |
Conviencency method, passing args from a goal constraint. More... | |
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.
constraint | to apply offset to |
offset | to apply to the constraint |
orientation | to apply to the offset |
Definition at line 591 of file trajectory_functions.cpp.
Eigen::Isometry3d getConstraintPose | ( | const moveit_msgs::msg::Constraints & | goal | ) |
Conviencency method, passing args from a goal constraint.
goal | goal constraint |
Definition at line 608 of file trajectory_functions.cpp.
void normalizeQuaternion | ( | geometry_msgs::msg::Quaternion & | quat | ) |
Definition at line 584 of file trajectory_functions.cpp.