Class ScrewAxis
Defined in File screw_motion.hpp
Class Documentation
-
class ScrewAxis
Public Functions
-
ScrewAxis(const std::string moving_frame_name, bool is_pure_translation = false)
-
bool setScrewAxis(const geometry_msgs::msg::Pose &origin_pose, const geometry_msgs::msg::Pose &axis_pose, double pitch = 0)
Sets up the Screw axis, using an axis defined by a line between 2 poses.
- Parameters:
origin_pose – The first pose will be used as the origin of the Screw. This must be defined with respect to the Screw’s frame
axis_pose – The second pose is just needed to define an axis. This must be defined with respect to the Screw’s frame
pitch – Sets the pitch of the screw
- Returns:
True if the setup was successful, false otherwise
-
inline bool setScrewAxis(const Eigen::Isometry3d &origin_pose, const Eigen::Isometry3d &axis_pose, double pitch = 0)
-
bool setScrewAxis(const geometry_msgs::msg::Pose &origin_pose, const Eigen::Vector3d &axis, double pitch = 0)
Sets up the Screw axis, using an axis defined pose and a vector.
- Parameters:
origin_pose – The first pose will be used as the origin of the Screw. This must be defined with respect to the Screw’s frame
axis – Sets the axis of the screw. This must be defined with respect to the Screw’s frame
pitch – Sets the pitch of the screw
- Returns:
True if the setup was successful, false otherwise
-
inline bool setScrewAxis(const Eigen::Isometry3d &origin_pose, const Eigen::Vector3d &axis, double pitch = 0)
-
geometry_msgs::msg::TwistStamped getTwist(double theta_dot) const
Sets up the Screw axis, a twist message (TODO: implement)
Gets the Twist corresponding to moving along this screw axis at the given velocity
- Parameters:
twist – The twist gets normalized based on whether or not the Screw is purely translational
pitch – Sets the pitch of the screw
theta_dot – The “velocity” (linear or rotational) to move
- Returns:
True if the setup was successful, false otherwise
- Returns:
The calculated twist, defined with respect to the frame of the Screw Axis
-
Eigen::Isometry3d getTF(double delta_theta) const
Gets the transform corresponding to moving along this screw axis for a given displacement.
- Parameters:
delta_theta – The “displacement” (linear or rotational) to move
- Returns:
The calculated transformation, defined with respect to the frame of the Screw Axis
-
inline std::string getFrame() const
-
inline Eigen::Vector3d getQVector() const
-
inline Eigen::Vector3d getAxis() const
-
inline Eigen::Vector3d getLinearVector() const
-
inline double getPitch() const
-
ScrewAxis(const std::string moving_frame_name, bool is_pure_translation = false)