|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <pilz_industrial_motion_planner/trajectory_functions.h>#include <moveit/planning_scene/planning_scene.h>#include <tf2/LinearMath/Quaternion.h>#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>#include <tf2_eigen/tf2_eigen.hpp>#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
Go to the source code of this file.
Functions | |
| 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 596 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 613 of file trajectory_functions.cpp.

| void normalizeQuaternion | ( | geometry_msgs::msg::Quaternion & | quat | ) |
Definition at line 589 of file trajectory_functions.cpp.
