39#include <rclcpp/rclcpp.hpp>
63 bool waitForExecution(
const rclcpp::Duration& timeout = rclcpp::Duration(0.0))
override
116 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
118 return std::make_shared<TestMoveItControllerHandle>(name);
125 names.push_back(it->first);
133 names.push_back(it->first);
141 moveit_controller_manager::Ros2ControlManager::ControllerState
getControllerState(
const std::string& name)
override
143 moveit_controller_manager::Ros2ControlManager::ControllerState state;
145 state.default_ =
false;
149 bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
override
151 for (
const std::string& controller : deactivate)
154 std::cout <<
"Deactivated controller " << controller <<
'\n';
156 for (
const std::string& controller : activate)
159 std::cout <<
"Activated controller " << controller <<
'\n';
MoveIt sends commands to a controller via a handle that satisfies this interface.
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
TestMoveItControllerHandle(const std::string &name)
bool cancelExecution() override
Cancel the execution of any motion using this controller.
bool waitForExecution(const rclcpp::Duration &timeout=rclcpp::Duration(0.0)) override
Wait for the current execution to complete, or until the timeout is reached.
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Return the execution status of the last trajectory sent to the controller.
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &) override
Send a trajectory to the controller.
void initialize(const rclcpp::Node::SharedPtr &) override
moveit_controller_manager::Ros2ControlManager::ControllerState getControllerState(const std::string &name) override
void getControllerJoints(const std::string &name, std::vector< std::string > &joints) override
bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate) override
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name) override
void getControllersList(std::vector< std::string > &names) override
std::map< std::string, std::vector< std::string > > controller_joints_
void getActiveControllers(std::vector< std::string > &names) override
std::map< std::string, int > controllers_
The reported execution status.