39 #include <sensor_msgs/JointState.h> 87 virtual moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
98 names[0] =
"my_example_controller";
107 getControllersList(names);
115 getControllersList(names);
124 if (name ==
"my_example_controller")
127 joints.push_back(
"joint1");
128 joints.push_back(
"joint2");
129 joints.push_back(
"joint3");
130 joints.push_back(
"joint4");
148 virtual bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
155 std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>
controllers_;
virtual ~MoveItControllerManagerExample()
PLUGINLIB_EXPORT_CLASS(moveit_controller_manager_example::MoveItControllerManagerExample, moveit_controller_manager::MoveItControllerManager)
MoveItControllerManagerExample()
ExampleControllerHandle(const std::string &name)
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
virtual void getControllersList(std::vector< std::string > &names)
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
virtual void getLoadedControllers(std::vector< std::string > &names)
ros::NodeHandle node_handle_
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
virtual void getActiveControllers(std::vector< std::string > &names)
MoveItControllerHandle(const std::string &name)
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &t)
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
virtual bool waitForExecution(const ros::Duration &)
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > controllers_
virtual bool cancelExecution()