#include <behaviortree_cpp/action_node.h>
#include <behaviortree_cpp/bt_factory.h>
#include <moveit_msgs/msg/move_it_error_codes.hpp>
#include <moveit_studio_behavior_interface/behavior_context.hpp>
#include <moveit_studio_behavior_interface/check_for_error.hpp>
#include <moveit_studio_behavior/utils/ros_utils.hpp>
◆ kActivateControllerService
constexpr auto kActivateControllerService = "/ensure_controller_is_active" |
|
constexpr |
◆ kPauseServoService
constexpr auto kPauseServoService = "/servo_server/pause_servo" |
|
constexpr |
◆ kPortIDControllerName
constexpr auto kPortIDControllerName = "controller_name" |
|
constexpr |
◆ kServiceResponseMaxWait
constexpr auto kServiceResponseMaxWait = std::chrono::seconds(5) |
|
constexpr |
◆ kSwitchServoCommandTypeService
constexpr auto kSwitchServoCommandTypeService = "/servo_server/switch_command_type" |
|
constexpr |
◆ kTeleoperateSleepRate
constexpr auto kTeleoperateSleepRate = std::chrono::milliseconds(50) |
|
constexpr |