Class SpeedMotion
Defined in File speed_motion.hpp
Inheritance Relationships
Base Type
public as2::motionReferenceHandlers::BasicMotionReferenceHandler
(Class BasicMotionReferenceHandler)
Class Documentation
-
class SpeedMotion : public as2::motionReferenceHandlers::BasicMotionReferenceHandler
The SpeedMotion class is a motion reference handler that moves the robot at a given speed.
Public Functions
-
explicit SpeedMotion(as2::Node *node_ptr, const std::string &ns = "")
PositionMotion Constructor.
- Parameters:
node – as2::Node pointer.
-
inline ~SpeedMotion()
SpeedMotion Destructor.
-
bool ownSendCommand()
ownSendCommand sends pose and twist messages.
- Returns:
true if commands was sent successfully, false otherwise.
-
bool sendSpeedCommandWithYawAngle(const std::string &frame_id_speed, const float &vx, const float &vy, const float &vz, const std::string &frame_id_yaw, const float &yaw_angle)
sendSpeedCommandWithYawAngle sends a speed command to the robot. The speed command is sent in the input frame id. The linear velocity is given in m/s.
- Parameters:
frame_id_speed – frame id of the velocity command.
vx – Linear velocity in the x axis.
vy – Linear velocity in the y axis.
vz – Linear velocity in the z axis.
frame_id_yaw – frame id of the yaw angle command.
yaw_angle – Yaw angle in radians.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendSpeedCommandWithYawAngle(const std::string &frame_id_speed, const float &vx, const float &vy, const float &vz, const std::string &frame_id_yaw, const geometry_msgs::msg::Quaternion &q)
sendSpeedCommandWithYawAngle sends a speed command to the robot. The speed command is sent in the input frame id. The linear velocity is given in m/s.
- Parameters:
frame_id_speed – frame id of the velocity command.
vx – Linear velocity in the x axis.
vy – Linear velocity in the y axis.
vz – Linear velocity in the z axis.
frame_id_yaw – frame id of the yaw angle command.
q – Quaternion that represents the yaw angle.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendSpeedCommandWithYawAngle(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist)
sendSpeedCommandWithYawAngle sends a speed command to the robot. The speed command is sent in the frame id frame. The linear velocity is given in m/s.
- Parameters:
pose – PoseStamped message that represents the rotation .
twist – TwistStamped message that represents the linear velocity.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendSpeedCommandWithYawSpeed(const std::string &frame_id, const float &vx, const float &vy, const float &vz, const float &yaw_speed)
sendSpeedCommandWithYawSpeed sends a speed command to the robot. The speed command is sent in the input frame id. The linear velocity is given in m/s. The yaw speed is given in rad/s.
- Parameters:
frame_id – frame id of the velocity command.
vx – Linear velocity in the x axis.
vy – Linear velocity in the y axis.
vz – Linear velocity in the z axis.
yaw_speed – Yaw speed in rad/s.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendSpeedCommandWithYawSpeed(const geometry_msgs::msg::TwistStamped &twist)
sendSpeedCommandWithYawSpeed sends a speed command to the robot. The speed command is sent in the frame id frame. The linear velocity is given in m/s. The yaw speed is given in rad/s.
- Parameters:
twist – TwistStamped message that represents the linear velocity and the angular yaw speed
- Returns:
true if the command was sent successfully, false otherwise.
-
explicit SpeedMotion(as2::Node *node_ptr, const std::string &ns = "")