moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_moveit_controller_manager.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
37#pragma once
38
39#include <rclcpp/rclcpp.hpp>
41#include <iostream>
42#include <map>
43
45{
47{
48public:
49 TestMoveItControllerHandle(const std::string& name) : MoveItControllerHandle(name)
50 {
51 }
52
53 bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory& /*trajectory*/) override
54 {
55 return true;
56 }
57
58 bool cancelExecution() override
59 {
60 return true;
61 }
62
63 bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(0.0)) override
64 {
65 (void)timeout;
66 return false;
67 }
68
73};
74
75class TestRos2ControlManager : public moveit_controller_manager::Ros2ControlManager
76{
77public:
78 static const int ACTIVE = 1;
79 static const int DEFAULT = 2;
80
82 {
83 controllers_["right_arm"] = DEFAULT;
84 controllers_["left_arm"] = ACTIVE + DEFAULT;
85 controllers_["arms"] = 0;
86 controllers_["base"] = DEFAULT;
87 controllers_["head"] = 0;
88 controllers_["left_arm_head"] = 0;
89
90 controller_joints_["right_arm"].push_back("rj1");
91 controller_joints_["right_arm"].push_back("rj2");
92
93 controller_joints_["left_arm"].push_back("lj1");
94 controller_joints_["left_arm"].push_back("lj2");
95 controller_joints_["left_arm"].push_back("lj3");
96
97 controller_joints_["arms"].insert(controller_joints_["arms"].end(), controller_joints_["left_arm"].begin(),
98 controller_joints_["left_arm"].end());
99 controller_joints_["arms"].insert(controller_joints_["arms"].end(), controller_joints_["right_arm"].begin(),
100 controller_joints_["right_arm"].end());
101
102 controller_joints_["base"].push_back("basej");
103 controller_joints_["head"].push_back("headj");
104
105 controller_joints_["left_arm_head"].insert(controller_joints_["left_arm_head"].end(),
106 controller_joints_["left_arm"].begin(),
107 controller_joints_["left_arm"].end());
108 controller_joints_["left_arm_head"].insert(controller_joints_["left_arm_head"].end(),
109 controller_joints_["head"].begin(), controller_joints_["head"].end());
110 }
111
112 void initialize(const rclcpp::Node::SharedPtr& /* node */) override
113 {
114 }
115
116 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
117 {
118 return std::make_shared<TestMoveItControllerHandle>(name);
119 }
120
121 void getControllersList(std::vector<std::string>& names) override
122 {
123 names.clear();
124 for (std::map<std::string, int>::const_iterator it = controllers_.begin(); it != controllers_.end(); ++it)
125 names.push_back(it->first);
126 }
127
128 void getActiveControllers(std::vector<std::string>& names) override
129 {
130 names.clear();
131 for (std::map<std::string, int>::const_iterator it = controllers_.begin(); it != controllers_.end(); ++it)
132 if (it->second & ACTIVE)
133 names.push_back(it->first);
134 }
135
136 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
137 {
138 joints = controller_joints_[name];
139 }
140
141 moveit_controller_manager::Ros2ControlManager::ControllerState getControllerState(const std::string& name) override
142 {
143 moveit_controller_manager::Ros2ControlManager::ControllerState state;
144 state.active_ = controllers_[name] & ACTIVE;
145 state.default_ = false;
146 return state;
147 }
148
149 bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
150 {
151 for (const std::string& controller : deactivate)
152 {
153 controllers_[controller] &= ~ACTIVE;
154 std::cout << "Deactivated controller " << controller << '\n';
155 }
156 for (const std::string& controller : activate)
157 {
158 controllers_[controller] |= ACTIVE;
159 std::cout << "Activated controller " << controller << '\n';
160 }
161 return true;
162 }
163
164protected:
165 std::map<std::string, int> controllers_;
166 std::map<std::string, std::vector<std::string> > controller_joints_;
167};
168} // namespace test_moveit_controller_manager
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.
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