Class PlayMotion2Client
Defined in File client.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class PlayMotion2Client : public rclcpp::Node
A client Node for the PlayMotion2 action server. This node provides methods to run motions, check if a motion is running, and manage motions (add, remove, list, check readiness).
Public Functions
-
explicit PlayMotion2Client(const std::string &name = "play_motion2_client", const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
Constructor for the PlayMotion2Client.
- Parameters:
name – The name of the node (defaults to “play_motion2_client”).
options – Node options for configuration.
-
~PlayMotion2Client()
Destructor for the PlayMotion2Client.
-
bool run_motion(const std::string &motion_name, const bool skip_planning, const std::chrono::seconds &motion_timeout = std::chrono::seconds(120))
Run a motion by its name.
- Parameters:
motion_name – The name of the motion to run.
skip_planning – If true, skip the planning phase.
motion_timeout – Optional. The timeout for the motion execution (defaults to 120).
- Returns:
True if the motion was successfully started, false otherwise.
-
bool run_motion_async(const std::string &motion_name, const bool skip_planning)
Run a motion asynchronously by its name.
- Parameters:
motion_name – The name of the motion to run.
skip_planning – If true, skip the planning phase.
- Returns:
True if the motion was successfully started, false otherwise.
-
bool run_motion(const play_motion2_msgs::msg::Motion &motion, const bool skip_planning, const std::chrono::seconds &motion_timeout = std::chrono::seconds(120))
Run a non-stored motion.
- Parameters:
motion – The motion to run.
skip_planning – If true, skip the planning phase.
motion_timeout – Optional. The timeout for the motion execution (defaults to 120).
- Returns:
True if the motion was successfully started, false otherwise.
-
bool run_motion_async(const play_motion2_msgs::msg::Motion &motion, const bool skip_planning)
Run a non-stored motion asynchronously.
- Parameters:
motion – The motion to run.
skip_planning – If true, skip the planning phase.
- Returns:
True if the motion was successfully started, false otherwise.
-
bool is_running_motion() const
Check if there is a motion currently running on the system.
- Returns:
True if a motion is running, false otherwise.
-
bool last_succeeded() const
Check if the last motion execution was successful.
- Returns:
True if the last motion succeeded, false otherwise.
-
std::vector<std::string> list_motions()
List all available motions.
- Returns:
A vector of motion keys (names) available in the system.
-
bool is_motion_ready(const std::string &motion_key)
Check if a specific motion is ready to be executed.
- Parameters:
motion_key – The key (name) of the motion to check.
- Returns:
True if the motion is ready, false otherwise.
-
MotionInfo get_motion_info(const std::string &motion_key)
Get detailed information about a specific motion.
- Parameters:
motion_key – The key (name) of the motion to retrieve information for.
- Returns:
A MotionInfo object containing details about the motion.
-
bool add_motion(const MotionMsg &motion_msg, const bool overwrite)
Add a new motion to the system.
- Parameters:
motion_msg – The MotionMsg object containing the motion details.
overwrite – If true, overwrite an existing motion with the same key.
- Returns:
True if the motion was successfully added, false otherwise.
-
bool remove_motion(const std::string &motion_key)
Remove a motion from the system.
- Parameters:
motion_key – The key (name) of the motion to remove.
- Returns:
True if the motion was successfully removed, false otherwise.
-
explicit PlayMotion2Client(const std::string &name = "play_motion2_client", const rclcpp::NodeOptions &options = rclcpp::NodeOptions())