MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
servo_utils.hpp File Reference
#include <moveit_msgs/srv/servo_command_type.hpp>
#include <rclcpp/client.hpp>
#include <std_srvs/srv/set_bool.hpp>
#include <string>
#include <tl_expected/expected.hpp>
Include dependency graph for servo_utils.hpp:
This graph shows which files directly or indirectly include this file:

Namespaces

 moveit_studio
 
 moveit_studio::behaviors
 

Functions

tl::expected< void, std::string > moveit_studio::behaviors::requestSwitchCommandType (std::shared_ptr< rclcpp::Client< moveit_msgs::srv::ServoCommandType >> client, std::shared_ptr< moveit_msgs::srv::ServoCommandType::Request > request)
 Send a request through a service client for a moveit_msgs::srv::ServoCommandType service and block until a response is received or a timeout limit is reached. More...
 
tl::expected< void, std::string > moveit_studio::behaviors::startServo (std::shared_ptr< rclcpp::Client< std_srvs::srv::SetBool >> client)
 Starts the servo node. More...
 
tl::expected< void, std::string > moveit_studio::behaviors::stopServo (std::shared_ptr< rclcpp::Client< std_srvs::srv::SetBool >> client)
 Stops the servo node. More...