Class TrajectoryMotion
Defined in File trajectory_motion.hpp
Inheritance Relationships
Base Type
public as2::motionReferenceHandlers::BasicMotionReferenceHandler
(Class BasicMotionReferenceHandler)
Class Documentation
-
class TrajectoryMotion : public as2::motionReferenceHandlers::BasicMotionReferenceHandler
The TrajectoryMotion class is a motion reference handler that sends a puntual trajectory reference to the robot. The trajectory point is given by a position, a yaw angle, a velocity and a acceleration.
Public Functions
-
explicit TrajectoryMotion(as2::Node *node_ptr, const std::string &ns = "")
TrajectoryMotion constructor.
- Parameters:
node – as2::Node pointer.
-
inline ~TrajectoryMotion()
TrajectoryMotion destructor.
-
bool sendTrajectoryCommandWithYawAngle(const std::string &frame_id, const double x, const double y, const double z, const double yaw_angle, const double vx, const double vy, const double vz, const double ax, const double ay, const double az)
sendTrajectoryCommandWithYawAngle sends a trajectory command to the robot.
- Parameters:
frame_id – frame id of trayectory point.
x – x coordinate of the trajectory point.
y – y coordinate of the trajectory point.
z – z coordinate of the trajectory point.
yaw_angle – yaw angle of the trajectory point.
vx – x velocity of the trajectory point.
vy – y velocity of the trajectory point.
vz – z velocity of the trajectory point.
ax – x acceleration of the trajectory point.
ay – y acceleration of the trajectory point.
az – z acceleration of the trajectory point.
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendTrajectoryCommandWithYawAngle(const std::string &frame_id, const double yaw_angle, const std::vector<double> &positions, const std::vector<double> &velocities, const std::vector<double> &accelerations)
sendTrajectoryCommandWithYawAngle sends a trajectory command to the robot.
- Parameters:
frame_id – frame id of trayectory point.
yaw_angle – yaw angle of the trajectory point.
positions – vector of positions of the trajectory point (x,y,z).
velocities – vector of velocities of the trajectory point (vx,vy,vz).
accelerations – vector of accelerations of the trajectory point (ax,ay,az).
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendTrajectoryCommandWithYawAngle(const std::string &frame_id, const double yaw_angle, const Eigen::Vector3d &positions, const Eigen::Vector3d &velocities, const Eigen::Vector3d &accelerations)
sendTrajectoryCommandWithYawAngle sends a trajectory command to the robot.
- Parameters:
frame_id – frame id of trayectory point.
yaw_angle – yaw angle of the trajectory point.
positions – vector of positions of the trajectory point (x,y,z).
velocities – vector of velocities of the trajectory point (vx,vy,vz).
accelerations – vector of accelerations of the trajectory point (ax,ay,az).
- Returns:
true if the command was sent successfully, false otherwise.
-
bool sendTrajectorySetpoints(const as2_msgs::msg::TrajectorySetpoints &trajectory_setpoints)
sendTrajectorySetpoints sends a trajectory setpoints message to the robot.
- Parameters:
trajectory_setpoints – trajectory setpoints message.
- Returns:
true if the command was sent successfully, false otherwise.
-
explicit TrajectoryMotion(as2::Node *node_ptr, const std::string &ns = "")