Class PositionMotion
Defined in File position_motion.hpp
Inheritance Relationships
Base Type
public as2::motionReferenceHandlers::BasicMotionReferenceHandler
(Class BasicMotionReferenceHandler)
Class Documentation
-
class PositionMotion : public as2::motionReferenceHandlers::BasicMotionReferenceHandler
The PositionMotion class is a motion reference handler that moves the robot to a given position.
Public Functions
-
explicit PositionMotion(as2::Node *node_ptr, const std::string &ns = "")
PositionMotion Constructor.
- Parameters:
node – as2::Node pointer.
-
inline ~PositionMotion()
PositionMotion Destructor.
-
bool ownSendCommand()
ownSendCommand sends the pose and twist messages.
- Returns:
true if commands was sent successfully, false otherwise.
-
bool sendPositionCommandWithYawAngle(const std::string &frame_id_pose, const float &x, const float &y, const float &z, const float &yaw_angle, const std::string &frame_id_twist, const float &vx, const float &vy, const float &vz)
sendPositionCommandWithYawAngle sends a position command to the robot. The yaw angle is given in radians. The linear velocity limitation is given in m/s. The position command and the velocity limitation are sent in the input frame id.
- Parameters:
frame_id_pose – frame id of the position command.
x – x coordinate of the position command.
y – y coordinate of the position command.
z – z coordinate of the position command.
yaw_angle – yaw angle of the position command.
frame_id_twist – frame id of the velocity limitation.
vx – linear velocity limitation in x direction.
vy – linear velocity limitation in y direction.
vz – linear velocity limitation in z direction.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendPositionCommandWithYawAngle(const std::string &frame_id_pose, const float &x, const float &y, const float &z, const geometry_msgs::msg::Quaternion &q, const std::string &frame_id_twist, const float &vx, const float &vy, const float &vz)
sendPositionCommandWithYawAngle sends a position command to the robot. The yaw angle is given in a quaternion. The linear velocity is given in m/s. The position command and the velocity limitation are sent in the input frame id.
- Parameters:
frame_id_pose – frame id of the position command.
x – x coordinate of the position command.
y – y coordinate of the position command.
z – z coordinate of the position command.
q – quaternion of the position command. (with the desired yaw angle).
frame_id_twist – frame id of the velocity limitation.
vx – linear velocity limitation in x direction.
vy – linear velocity limitation in y direction.
vz – linear velocity limitation in z direction.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendPositionCommandWithYawAngle(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist)
sendPositionCommandWithYawAngle sends a position command to the robot. The position command is sent in the frame id frame.
- Parameters:
pose – geometry_msgs::msg::PoseStamped with the desired position and yaw angle.
twist – geometry_msgs::msg::TwistStamped with the desired linear velocity.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendPositionCommandWithYawSpeed(const std::string &frame_id_pose, const float &x, const float &y, const float &z, const float &yaw_speed, const std::string &frame_id_twist, const float &vx, const float &vy, const float &vz)
sendPositionCommandWithYawSpeed sends a position command to the robot. The yaw speed is given in rad/s. The linear velocity is given in m/s. The position command and the velocity limitation are sent in the input frame id.
- Parameters:
frame_id_pose – frame id of the position command.
x – x coordinate of the position command.
y – y coordinate of the position command.
z – z coordinate of the position command.
yaw_speed – yaw speed of the position command.
frame_id_twist – frame id of the velocity limitation.
vx – linear velocity limitation in x direction.
vy – linear velocity limitation in y direction.
vz – linear velocity limitation in z direction.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendPositionCommandWithYawSpeed(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist)
sendPositionCommandWithYawSpeed sends a position command to the robot. The position command is sent in the frame id frame.
- Parameters:
x – pose geometry_msgs::msg::PoseStamped with the desired position.
twist – geometry_msgs::msg::TwistStamped with the desired linear velocity and yaw speed.
- Returns:
true if the command was sent successfully, false otherwise.
-
explicit PositionMotion(as2::Node *node_ptr, const std::string &ns = "")