moveit_fake_controller_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
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 Ioan A. Sucan 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, Dave Coleman, Robert Haschke */
36 
38 #include <ros/ros.h>
41 #include <sensor_msgs/JointState.h>
43 #include <ros/console.h>
44 #include <map>
45 
47 {
48 static const std::string DEFAULT_TYPE = "interpolate";
49 static const std::string ROBOT_DESCRIPTION = "robot_description";
50 
52 {
53 public:
55  {
56  if (!node_handle_.hasParam("controller_list"))
57  {
58  ROS_ERROR_STREAM_NAMED("MoveItFakeControllerManager", "No controller_list specified.");
59  return;
60  }
61 
62  XmlRpc::XmlRpcValue controller_list;
63  node_handle_.getParam("controller_list", controller_list);
64  if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
65  {
66  ROS_ERROR_NAMED("MoveItFakeControllerManager", "controller_list should be specified as an array");
67  return;
68  }
69 
70  /* by setting latch to true we preserve the initial joint state while other nodes launch */
71  bool latch = true;
72  pub_ = node_handle_.advertise<sensor_msgs::JointState>("fake_controller_joint_states", 100, latch);
73 
74  /* publish initial pose */
75  XmlRpc::XmlRpcValue initial;
76  if (node_handle_.getParam("initial", initial))
77  {
78  sensor_msgs::JointState js = loadInitialJointValues(initial);
79  js.header.stamp = ros::Time::now();
81  }
82 
83  /* actually create each controller */
84  for (int i = 0; i < controller_list.size(); ++i) // NOLINT(modernize-loop-convert)
85  {
86  if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
87  {
88  ROS_ERROR_NAMED("MoveItFakeControllerManager", "Name and joints must be specified for each controller");
89  continue;
90  }
91 
92  try
93  {
94  const std::string name = std::string(controller_list[i]["name"]);
95 
96  if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
97  {
98  ROS_ERROR_STREAM_NAMED("MoveItFakeControllerManager",
99  "The list of joints for controller " << name << " is not specified as an array");
100  continue;
101  }
102  std::vector<std::string> joints;
103  joints.reserve(controller_list[i]["joints"].size());
104  for (int j = 0; j < controller_list[i]["joints"].size(); ++j)
105  joints.emplace_back(std::string(controller_list[i]["joints"][j]));
106 
107  const std::string& type =
108  controller_list[i].hasMember("type") ? std::string(controller_list[i]["type"]) : DEFAULT_TYPE;
109  if (type == "last point")
110  controllers_[name] = std::make_shared<LastPointController>(name, joints, pub_);
111  else if (type == "via points")
112  controllers_[name] = std::make_shared<ViaPointController>(name, joints, pub_);
113  else if (type == "interpolate")
114  controllers_[name] = std::make_shared<InterpolatingController>(name, joints, pub_);
115  else
116  ROS_ERROR_STREAM("Unknown fake controller type: " << type);
117 
119  state.default_ = controller_list[i].hasMember("default") ? (bool)controller_list[i]["default"] : false;
120  state.active_ = true;
121 
122  controller_states_[name] = state;
123  }
124  catch (...)
125  {
126  ROS_ERROR_NAMED("MoveItFakeControllerManager", "Caught unknown exception while parsing controller information");
127  }
128  }
129  }
130 
131  sensor_msgs::JointState loadInitialJointValues(XmlRpc::XmlRpcValue& param) const
132  {
133  sensor_msgs::JointState js;
134 
135  if (param.getType() != XmlRpc::XmlRpcValue::TypeArray || param.size() == 0)
136  {
137  ROS_ERROR_ONCE_NAMED("loadInitialJointValues", "Parameter 'initial' should be an array of (group, pose) "
138  "structs.");
139  return js;
140  }
141 
143  const moveit::core::RobotModelPtr& robot_model = robot_model_loader.getModel();
144  moveit::core::RobotState robot_state(robot_model);
145  typedef std::map<std::string, double> JointPoseMap;
146  JointPoseMap joints;
147 
148  robot_state.setToDefaultValues(); // initialize all joint values (just in case...)
149  for (int i = 0, end = param.size(); i != end; ++i)
150  {
151  try
152  {
153  std::string group_name = std::string(param[i]["group"]);
154  std::string pose_name = std::string(param[i]["pose"]);
155  if (!robot_model->hasJointModelGroup(group_name))
156  {
157  ROS_WARN_STREAM_NAMED("loadInitialJointValues", "Unknown joint model group: " << group_name);
158  continue;
159  }
160  moveit::core::JointModelGroup* jmg = robot_model->getJointModelGroup(group_name);
161  const std::vector<std::string>& joint_names = jmg->getActiveJointModelNames();
162 
163  if (!robot_state.setToDefaultValues(jmg, pose_name))
164  {
165  ROS_WARN_NAMED("loadInitialJointValues", "Unknown pose '%s' for group '%s'.", pose_name.c_str(),
166  group_name.c_str());
167  continue;
168  }
169  ROS_INFO_NAMED("loadInitialJointValues", "Set joints of group '%s' to pose '%s'.", group_name.c_str(),
170  pose_name.c_str());
171 
172  for (const std::string& joint_name : joint_names)
173  {
174  const moveit::core::JointModel* jm = robot_state.getJointModel(joint_name);
175  if (!jm)
176  {
177  ROS_WARN_STREAM_NAMED("loadInitialJointValues", "Unknown joint: " << joint_name);
178  continue;
179  }
180  if (jm->getVariableCount() != 1)
181  {
182  ROS_WARN_STREAM_NAMED("loadInitialJointValues", "Cannot handle multi-variable joint: " << joint_name);
183  continue;
184  }
185 
186  joints[joint_name] = robot_state.getJointPositions(jm)[0];
187  }
188  }
189  catch (...)
190  {
191  ROS_ERROR_ONCE_NAMED("loadInitialJointValues", "Caught unknown exception while reading initial pose "
192  "information.");
193  }
194  }
195 
196  // fill the joint state
197  for (const auto& name_pos_pair : joints)
198  {
199  js.name.push_back(name_pos_pair.first);
200  js.position.push_back(name_pos_pair.second);
201  }
202  return js;
203  }
204 
205  ~MoveItFakeControllerManager() override = default;
206 
207  /*
208  * Get a controller, by controller name (which was specified in the controllers.yaml
209  */
210  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
211  {
212  std::map<std::string, BaseFakeControllerPtr>::const_iterator it = controllers_.find(name);
213  if (it != controllers_.end())
214  return it->second;
215  else
216  ROS_FATAL_STREAM("No such controller: " << name);
217  return moveit_controller_manager::MoveItControllerHandlePtr();
218  }
219 
220  /*
221  * Get the list of controller names.
222  */
223  void getControllersList(std::vector<std::string>& names) override
224  {
225  for (std::map<std::string, BaseFakeControllerPtr>::const_iterator it = controllers_.begin();
226  it != controllers_.end(); ++it)
227  names.push_back(it->first);
228  ROS_INFO_STREAM("Returned " << names.size() << " controllers in list");
229  }
230 
231  /*
232  * Fake controllers are always active
233  */
234  void getActiveControllers(std::vector<std::string>& names) override
235  {
236  getControllersList(names);
237  }
238 
239  /*
240  * Fake controllers are always loaded
241  */
242  virtual void getLoadedControllers(std::vector<std::string>& names)
243  {
244  getControllersList(names);
245  }
246 
247  /*
248  * Get the list of joints that a controller can control.
249  */
250  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
251  {
252  std::map<std::string, BaseFakeControllerPtr>::const_iterator it = controllers_.find(name);
253  if (it != controllers_.end())
254  {
255  it->second->getJoints(joints);
256  }
257  else
258  {
259  ROS_WARN("The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on "
260  "the param server?",
261  name.c_str());
262  joints.clear();
263  }
264  }
265 
267  getControllerState(const std::string& name) override
268  {
269  return controller_states_[name];
270  }
271 
272  /* Cannot switch our controllers */
273  bool switchControllers(const std::vector<std::string>& /*activate*/,
274  const std::vector<std::string>& /*deactivate*/) override
275  {
276  return false;
277  }
278 
279 protected:
282  std::map<std::string, BaseFakeControllerPtr> controllers_;
283  std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState> controller_states_;
284 };
285 
286 } // end namespace moveit_fake_controller_manager
287 
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
XmlRpc::XmlRpcValue::size
int size() const
moveit_fake_controller_manager::MoveItFakeControllerManager::getControllerHandle
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name) override
Definition: moveit_fake_controller_manager.cpp:242
ros::Publisher
moveit::core::JointModel::getVariableCount
std::size_t getVariableCount() const
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
moveit::core::JointModelGroup::getActiveJointModelNames
const std::vector< std::string > & getActiveJointModelNames() const
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
ros.h
robot_model_loader
moveit_fake_controller_manager::MoveItFakeControllerManager::controllers_
std::map< std::string, BaseFakeControllerPtr > controllers_
Definition: moveit_fake_controller_manager.cpp:314
moveit_controller_manager::MoveItControllerManager::ControllerState::active_
bool active_
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
robot_model_loader.h
robot_state.h
moveit_fake_controllers.h
moveit_fake_controller_manager::MoveItFakeControllerManager::controller_states_
std::map< std::string, moveit_controller_manager::MoveItControllerManager::ControllerState > controller_states_
Definition: moveit_fake_controller_manager.cpp:315
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ROS_ERROR_ONCE_NAMED
#define ROS_ERROR_ONCE_NAMED(name,...)
moveit_fake_controller_manager::MoveItFakeControllerManager::getControllerJoints
void getControllerJoints(const std::string &name, std::vector< std::string > &joints) override
Definition: moveit_fake_controller_manager.cpp:282
moveit_fake_controller_manager::MoveItFakeControllerManager
Definition: moveit_fake_controller_manager.cpp:83
moveit_fake_controller_manager::MoveItFakeControllerManager::switchControllers
bool switchControllers(const std::vector< std::string > &, const std::vector< std::string > &) override
Definition: moveit_fake_controller_manager.cpp:305
console.h
robot_model_loader::RobotModelLoader
name
std::string name
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_fake_controller_manager::ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: moveit_fake_controller_manager.cpp:81
moveit_fake_controller_manager::MoveItFakeControllerManager::pub_
ros::Publisher pub_
Definition: moveit_fake_controller_manager.cpp:313
moveit_fake_controller_manager::MoveItFakeControllerManager::loadInitialJointValues
sensor_msgs::JointState loadInitialJointValues(XmlRpc::XmlRpcValue &param) const
Definition: moveit_fake_controller_manager.cpp:163
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
moveit_fake_controller_manager::MoveItFakeControllerManager::getControllersList
void getControllersList(std::vector< std::string > &names) override
Definition: moveit_fake_controller_manager.cpp:255
moveit_controller_manager::MoveItControllerManager
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
moveit_fake_controller_manager
Definition: moveit_fake_controller_manager.cpp:46
moveit_fake_controller_manager::MoveItFakeControllerManager::getActiveControllers
void getActiveControllers(std::vector< std::string > &names) override
Definition: moveit_fake_controller_manager.cpp:266
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
XmlRpc::XmlRpcValue::TypeArray
TypeArray
moveit_fake_controller_manager::DEFAULT_TYPE
static const std::string DEFAULT_TYPE
Definition: moveit_fake_controller_manager.cpp:80
moveit_fake_controller_manager::MoveItFakeControllerManager::node_handle_
ros::NodeHandle node_handle_
Definition: moveit_fake_controller_manager.cpp:312
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
moveit_fake_controller_manager::MoveItFakeControllerManager::~MoveItFakeControllerManager
~MoveItFakeControllerManager() override=default
moveit_fake_controller_manager::MoveItFakeControllerManager::getLoadedControllers
virtual void getLoadedControllers(std::vector< std::string > &names)
Definition: moveit_fake_controller_manager.cpp:274
class_list_macros.hpp
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::JointModelGroup
param
T param(const std::string &param_name, const T &default_val)
moveit_fake_controller_manager::MoveItFakeControllerManager::MoveItFakeControllerManager
MoveItFakeControllerManager()
Definition: moveit_fake_controller_manager.cpp:86
moveit::core::JointModel
XmlRpc::XmlRpcValue
ros::NodeHandle
moveit_fake_controller_manager::MoveItFakeControllerManager::getControllerState
moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name) override
Definition: moveit_fake_controller_manager.cpp:299
ros::Time::now
static Time now()
moveit_controller_manager::MoveItControllerManager::ControllerState::default_
bool default_


moveit_fake_controller_manager
Author(s): Ioan Sucan
autogenerated on Sat May 3 2025 02:26:28